-
Notifications
You must be signed in to change notification settings - Fork 80
Switch aux_global_position to AuxGlobalPosition message type #180
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
Changes from 2 commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -7,7 +7,7 @@ | |
|
|
||
| #include <Eigen/Eigen> | ||
| #include <optional> | ||
| #include <px4_msgs/msg/vehicle_global_position.hpp> | ||
| #include <px4_msgs/msg/aux_global_position.hpp> | ||
| #include <px4_ros2/navigation/experimental/navigation_interface_base.hpp> | ||
| #include <rclcpp/rclcpp.hpp> | ||
|
|
||
|
|
@@ -46,7 +46,14 @@ struct GlobalPositionMeasurement { | |
| */ | ||
| class GlobalPositionMeasurementInterface : public PositionMeasurementInterfaceBase { | ||
| public: | ||
| explicit GlobalPositionMeasurementInterface(rclcpp::Node& node, | ||
| /** | ||
| * @param id Unique identifier non-zero for this position source. PX4 uses this to demultiplex | ||
| * measurements from multiple external positioning sources on the same topic. | ||
| * @param source Source type of the position data, using AuxGlobalPosition::SOURCE_* | ||
| * constants. Defaults to SOURCE_VISION (2). | ||
| */ | ||
| explicit GlobalPositionMeasurementInterface(rclcpp::Node& node, uint8_t id = 1, | ||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Can you add API docs for the extra args and describe how to set them? And as a user I'd ask myself why do I have to set both source and id if they are just integers? Can't one be inferred from the other?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. GitBook PR
|
||
| uint8_t source = 2, | ||
| std::string topic_namespace_prefix = ""); | ||
| ~GlobalPositionMeasurementInterface() override = default; | ||
|
|
||
|
|
@@ -94,11 +101,12 @@ class GlobalPositionMeasurementInterface : public PositionMeasurementInterfaceBa | |
| */ | ||
| bool isValueNotNAN(const GlobalPositionMeasurement& measurement) const; | ||
|
|
||
| rclcpp::Publisher<px4_msgs::msg::VehicleGlobalPosition>::SharedPtr _aux_global_position_pub; | ||
| rclcpp::Publisher<px4_msgs::msg::AuxGlobalPosition>::SharedPtr _aux_global_position_pub; | ||
|
|
||
| const uint8_t _id; | ||
| const uint8_t _source; | ||
| uint8_t _lat_lon_reset_counter{ | ||
| 0}; /** Counter for reset events on horizontal position coordinates */ | ||
| // uint8_t _altitude_frame; | ||
| }; | ||
|
|
||
| /** @}*/ | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Would be good to change this to an enum then (defined here), which would make it easier to use.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The enum is defined in the AuxGlobalPosition message, do we really want to have duplicated enums?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
after discussion. yes it makes sense to use it