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

Bugfix/update map origin with home position #1892

Merged
Merged
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
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