Skip to content

Commit

Permalink
Bugfix/update map origin with home position (#1892)
Browse files Browse the repository at this point in the history
* Update map origin with home position

* Uncrustify

* Revert "Uncrustify"

This reverts commit f1387c7.

* Change to relative topic

---------

Co-authored-by: Natalia Molina <[email protected]>
  • Loading branch information
natmol and wico-molina authored Sep 6, 2023
1 parent 4a8cd45 commit cb8fafe
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion mavros/src/plugins/global_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ class GlobalPositionPlugin : public plugin::PluginBase {

GlobalPositionPlugin() : PluginBase(),
gp_nh("~global_position"),
hp_nh("~home_position"),
tf_send(false),
use_relative_alt(true),
is_map_init(false),
Expand Down Expand Up @@ -89,7 +90,7 @@ class GlobalPositionPlugin : public plugin::PluginBase {

// home position subscriber to set "map" origin
// TODO use UAS
hp_sub = gp_nh.subscribe("home", 10, &GlobalPositionPlugin::home_position_cb, this);
hp_sub = hp_nh.subscribe("home", 10, &GlobalPositionPlugin::home_position_cb, this);

// offset from local position to the global origin ("earth")
gp_global_offset_pub = gp_nh.advertise<geometry_msgs::PoseStamped>("gp_lp_offset", 10);
Expand All @@ -108,6 +109,7 @@ class GlobalPositionPlugin : public plugin::PluginBase {

private:
ros::NodeHandle gp_nh;
ros::NodeHandle hp_nh; //node handler in home_position namespace

ros::Publisher raw_fix_pub;
ros::Publisher raw_vel_pub;
Expand Down

0 comments on commit cb8fafe

Please sign in to comment.