Skip to content

Commit

Permalink
fix #638 - geotagging plugin not working: subscribed to wrong topic
Browse files Browse the repository at this point in the history
  • Loading branch information
igorsgcampos authored and TSC21 committed Oct 24, 2020
1 parent 9f832e5 commit 2451437
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion src/gazebo_geotagged_images_plugin.cpp
Expand Up @@ -141,7 +141,7 @@ void GeotaggedImagesPlugin::Load(sensors::SensorPtr sensor, sdf::ElementPtr sdf)
_newFrameConnection = _camera->ConnectNewImageFrame(
boost::bind(&GeotaggedImagesPlugin::OnNewFrame, this, _1));

_gpsSub = _node_handle->Subscribe("~/" + rootModelName + "/gps", &GeotaggedImagesPlugin::OnNewGpsPosition, this);
_gpsSub = _node_handle->Subscribe("~/" + rootModelName + "/link/gps", &GeotaggedImagesPlugin::OnNewGpsPosition, this);

_storageDir = "frames";
boost::filesystem::remove_all(_storageDir); //clear existing images
Expand Down

0 comments on commit 2451437

Please sign in to comment.