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

Conversation

natmol
Copy link
Contributor

@natmol natmol commented Aug 29, 2023

Updates the map_origin in the callback home_position_cb after new home has been updated from the FMU over the mavtlink message HOME_POSITION and in the ros topic /mavros/home_position/home

@@ -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 = nh.subscribe("/mavros/home_position/home", 10, &GlobalPositionPlugin::home_position_cb, this);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No! Node mustn't use absolute paths.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The Mavlink HOMEPOSITION message is handled by the home_position.cpp plugin.

image

This gets published in the topic /mavros/home_position/home.

Is it desired to create a handler in the global_position.cpp plugin for the same Mavlink topic?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

NodeHandle priv_nh("~");

sub = priv_nh.subscribe("home_position/home", ...);

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Or even:

NodeHandle hp_nh("~home_position");

sub = hp_nh.subscribe("home", ...);

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed

// GPS_STATUS: there no corresponding ROS message, and it is not supported by APM
make_handler(&GlobalPositionPlugin::handle_global_position_int),
make_handler(&GlobalPositionPlugin::handle_gps_global_origin),
make_handler(&GlobalPositionPlugin::handle_lpned_system_global_offset)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do not change style.

Copy link
Contributor Author

@natmol natmol Aug 29, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done. Style was changed by uncrustify

This reverts commit f1387c7.
@natmol natmol requested a review from vooon August 29, 2023 15:08
Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM, thanks!

@vooon vooon merged commit cb8fafe into mavlink:master Sep 6, 2023
2 of 3 checks passed
@vooon vooon added this to the Version 1.17 milestone Sep 6, 2023
vooon added a commit that referenced this pull request Sep 9, 2023
* master:
  1.17.0
  update changelog
  cog: regenerate all
  Bugfix/update map origin with home position (#1892)
  mavros: Remove extra ';'
  mavros_extras: Fix some init order warnings
  Suppress warnings from included headers
  1.16.0
  update changelog
  made it such that the gp_origin topic published latched.
  use hpp instead of deprecated .h pluginlib headers
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants