5yler / metatron

Autonomous Power Racing Series Racecar - ROS Metapackage
4 stars 2 forks source link

Integrate GPS with navigation stack #10

Open 5yler opened 7 years ago

5yler commented 7 years ago

navsat_transform_node takes as input a nav_msgs/Odometry message (usually the output of ekf_localization_node or ukf_localization_node), a sensor_msgs/Imu containing an accurate estimate of your robot's heading, and a sensor_msgs/NavSatFix message containing GPS data. It produces an odometry message in coordinates that are consistent with your robot's world frame. This value can be directly fused into your state estimate.

Tasks

5yler commented 7 years ago

Trying navsat_transform_node integration, which seems to give valid output on the command line:

[ INFO] [/navsat_transform_node:685]: Datum (latitude, longitude, altitude) is (42.342590, -71.056810, 14.700000)
[ INFO] [/navsat_transform_node:686]: Datum UTM coordinate is (330573.184516, 4689863.540046)
[ INFO] [/navsat_transform_node:698]: Initial odometry pose is Origin: (8.6485112107776167534 -4.4029022768916581398 0)
Rotation (RPY): (0, -0, 3.1147549935963128043)

However, doing rostopic echo /odometry/gps gives the following error:

WARNING: no messages received and simulated time is active.
Is /clock being published?

With GPS and navsat_transform_node:

image

Without GPS and navsat_transform_node:

image

It's possible that integrating GPS would be more accurate in a wide open area not surrounded by tall buildings. Further tests should be performed.