Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Gps with mapviz #68

Merged
merged 4 commits into from
Aug 11, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 7 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -251,4 +251,10 @@ endif ()
install_launch_macro()
if (COMMAND additional_install_macro)
additional_install_macro()
endif ()
endif ()

# Install Python scripts I ADDED THIS (TEST)
catkin_install_python(PROGRAMS
src/nav/gps.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
1 change: 1 addition & 0 deletions requirements.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
adafruit-circuitpython-gps
26 changes: 26 additions & 0 deletions src/nav/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
## NAVIGATIONAL SYSTEMS GUIDE

This guide will explain the step-by-step process on how to activate the rover's GPS and IMU, setup a mapproxy docker container to acquire and cache map tiles from Google Maps, and display his data through ROS's MapViz program.

NOTE: Remember to start an roscore instance and source the catkin workspace's devel/setup.bash file prior to inputting these commands.

## STEP #1: Starting up the GPS and IMU

cd ~/catkin_ws
rosrun uvic_rover gps.py

FURTHER INSTRUCTIONS TO BE ADDED

## STEP #2: Creating the Mapproxy Docker Container

sudo docker run -p 8080:8080 -d -t -v ~/mapproxy:/mapproxy danielsnider/mapproxy

OPTIONAL: To verify that the docker container was successfully created, use the following to list all running containers.

sudo docker ps

## STEP #3: Opening MapViz

roslaunch mapviz mapviz.launch


142 changes: 142 additions & 0 deletions src/nav/gps.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
#!/usr/bin/env python

# SPDX-FileCopyrightText: 2021 ladyada for Adafruit Industries
# SPDX-License-Identifier: MIT

# Simple GPS module demonstration.
# Will wait for a fix and print a message every second with the current location
# and other details.
import time
import adafruit_gps
import rospy
from sensor_msgs.msg import NavSatFix
from gps_common.msg import GPSFix
# Create a serial connection for the GPS connection using default speed and
# a slightly higher timeout (GPS modules typically update once a second).
# These are the defaults you should use for the GPS FeatherWing.
# For other boards set RX = GPS module TX, and TX = GPS module RX pins.
#uart = busio.UART(board.TX, board.RX, baudrate=9600, timeout=10)

# for a computer, use the pyserial library for uart access

import serial
def main():
uart = serial.Serial("/dev/ttyUSB0", baudrate=9600, timeout=10)
# Initialize GPS Ros node
rospy.init_node('gps_talker')

navsatfix_pub = rospy.Publisher('GPS_NavSatFix', NavSatFix, queue_size=10)
navsatfix_msg = NavSatFix()
navsatfix_msg.header.frame_id = "/map1" #used to be /map

common_pub = rospy.Publisher('GPS_Common', GPSFix, queue_size=10)
common_msg = GPSFix()
common_msg.header.frame_id = "/map2"

rate = rospy.Rate(1)
# Create a GPS module instance.
gps = adafruit_gps.GPS(uart, debug=False) # Use UART/pyserial
# gps = adafruit_gps.GPS_GtopI2C(i2c, debug=False) # Use I2C interface

# Initialize the GPS module by changing what data it sends and at what rate.
# These are NMEA extensions for PMTK_314_SET_NMEA_OUTPUT and
# PMTK_220_SET_NMEA_UPDATERATE but you can send anything from here to adjust
# the GPS module behavior:
# https://cdn-shop.adafruit.com/datasheets/PMTK_A11.pdf

# Turn on the basic GGA and RMC info (what you typically want)
gps.send_command(b"PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0")
# Turn on just minimum info (RMC only, location):
# gps.send_command(b'PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0')
# Turn off everything:
# gps.send_command(b'PMTK314,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0')
# Turn on everything (not all of it is parsed!)
# gps.send_command(b'PMTK314,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0')

# Set update rate to once a second (1hz) which is what you typically want.
gps.send_command(b"PMTK220,1000")
# Or decrease to once every two seconds by doubling the millisecond value.
# Be sure to also increase your UART timeout above!
# gps.send_command(b'PMTK220,2000')
# You can also speed up the rate, but don't go too fast or else you can lose
# data during parsing. This would be twice a second (2hz, 500ms delay):
# gps.send_command(b'PMTK220,500')

# Main loop runs forever printing the location, etc. every second.
last_print = time.monotonic()
while not rospy.is_shutdown():
# Make sure to call gps.update() every loop iteration and at least twice
# as fast as data comes from the GPS unit (usually every second).
# This returns a bool that's true if it parsed new data (you can ignore it
# though if you don't care and instead look at the has_fix property).
gps.update()
# Every second print out current location details if there's a fix.
current = time.monotonic()
if current - last_print >= 1.0:
last_print = current
if not gps.has_fix:
# Try again if we don't have a fix yet.
print("Waiting for fix...")
continue
# We have a fix! (gps.has_fix is true)

# Put gps data into navstat
navsatfix_msg.latitude = gps.latitude
navsatfix_msg.longitude = gps.longitude
navsatfix_msg.altitude = gps.altitude_m
navsatfix_msg.status.status = 1
navsatfix_msg.status.service = 1

common_msg.latitude = gps.latitude
common_msg.longitude = gps.longitude
common_msg.altitude = gps.altitude_m
common_msg.status.status = 1

navsatfix_pub.publish(navsatfix_msg)
common_pub.publish(common_msg)

# Print out details about the fix like location, date, etc.
print("=" * 40) # Print a separator line.
print(
"Fix UTC timestamp: {}/{}/{} {:02}:{:02}:{:02}".format(
gps.timestamp_utc.tm_mon, # Grab parts of the time from the
gps.timestamp_utc.tm_mday, # struct_time object that holds
gps.timestamp_utc.tm_year, # the fix time. Note you might
gps.timestamp_utc.tm_hour, # not get all data like year, day,
gps.timestamp_utc.tm_min, # month!
gps.timestamp_utc.tm_sec,
)
)
print("Latitude: {0:.6f} degrees".format(gps.latitude))
print("Longitude: {0:.6f} degrees".format(gps.longitude))
print(
"Precise Latitude: {:2.0f}{:2.4f} degrees".format(
gps.latitude_degrees, gps.latitude_minutes
)
)
print(
"Precise Longitude: {:2.0f}{:2.4f} degrees".format(
gps.longitude_degrees, gps.longitude_minutes
)
)
# print("Fix quality: {}".format(gps.fix_quality))
# # Some attributes beyond latitude, longitude and timestamp are optional
# # and might not be present. Check if they're None before trying to use!
# if gps.satellites is not None:
# print("# satellites: {}".format(gps.satellites))
# if gps.altitude_m is not None:
# print("Altitude: {} meters".format(gps.altitude_m))
# if gps.speed_knots is not None:
# print("Speed: {} knots".format(gps.speed_knots))
# if gps.track_angle_deg is not None:
# print("Track angle: {} degrees".format(gps.track_angle_deg))
# if gps.horizontal_dilution is not None:
# print("Horizontal dilution: {}".format(gps.horizontal_dilution))
# if gps.height_geoid is not None:
# print("Height geoid: {} meters".format(gps.height_geoid))

if __name__ == "__main__":
try:
main()
except rospy.ROSInterruptException:
pass
Loading