Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 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
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ using namespace std::chrono_literals; // NOLINT
{"fmu/in/actuator_motors"}, \
{"fmu/in/actuator_servos"}, \
{"fmu/in/arming_check_reply"}, \
{"fmu/in/aux_global_position", "VehicleGlobalPosition"}, \
{"fmu/in/aux_global_position"}, \
{"fmu/in/config_control_setpoints", "VehicleControlMode"}, \
{"fmu/in/config_overrides_request", "ConfigOverrides"}, \
{"fmu/in/fixed_wing_lateral_setpoint"}, \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down Expand Up @@ -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_*
Copy link
Copy Markdown
Collaborator

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.

enum class SourceType {
   Vision = AuxGlobalPosition::SOURCE_VISION,
};

Copy link
Copy Markdown
Contributor Author

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?

Copy link
Copy Markdown
Contributor Author

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

* constants. Defaults to SOURCE_VISION (2).
*/
explicit GlobalPositionMeasurementInterface(rclcpp::Node& node, uint8_t id = 1,
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The 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?
Is the id not starting with 0?

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?

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

GitBook PR

  • ID is not starting at 0. Zero is the default value of unpopulated params for unused sensors
  • The source type is propagated to downstream consumers in messages derived from this data. So mavlink etc want to know what the source type is. We decided against an ID "pattern" to store this knowledge in the ID. You can have multiple instances with the same source-type.

uint8_t source = 2,
std::string topic_namespace_prefix = "");
~GlobalPositionMeasurementInterface() override = default;

Expand Down Expand Up @@ -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;
};

/** @}*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,17 +7,19 @@
#include <px4_ros2/utils/message_version.hpp>

using Eigen::Vector2d;
using px4_msgs::msg::VehicleGlobalPosition;
using px4_msgs::msg::AuxGlobalPosition;

namespace px4_ros2 {

GlobalPositionMeasurementInterface::GlobalPositionMeasurementInterface(
rclcpp::Node& node, std::string topic_namespace_prefix)
: PositionMeasurementInterfaceBase(node, std::move(topic_namespace_prefix))
rclcpp::Node& node, uint8_t id, uint8_t source, std::string topic_namespace_prefix)
: PositionMeasurementInterfaceBase(node, std::move(topic_namespace_prefix)),
_id(id),
_source(source)
{
_aux_global_position_pub = node.create_publisher<VehicleGlobalPosition>(
_aux_global_position_pub = node.create_publisher<AuxGlobalPosition>(
topicNamespacePrefix() + "fmu/in/aux_global_position" +
px4_ros2::getMessageNameVersion<VehicleGlobalPosition>(),
px4_ros2::getMessageNameVersion<AuxGlobalPosition>(),
10);
}

Expand All @@ -42,7 +44,9 @@ void GlobalPositionMeasurementInterface::update(
}

// Populate aux global position
VehicleGlobalPosition aux_global_position;
AuxGlobalPosition aux_global_position;
aux_global_position.id = _id;
aux_global_position.source = _source;
aux_global_position.lat_lon_reset_counter = _lat_lon_reset_counter;

aux_global_position.timestamp_sample =
Expand Down
13 changes: 6 additions & 7 deletions px4_ros2_cpp/test/unit/global_navigation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,11 @@ class GlobalPositionInterfaceTest : public testing::Test {

_global_navigation_interface =
std::make_shared<px4_ros2::GlobalPositionMeasurementInterface>(*_node);
_subscriber = _node->create_subscription<px4_msgs::msg::VehicleGlobalPosition>(
_subscriber = _node->create_subscription<px4_msgs::msg::AuxGlobalPosition>(
"/fmu/in/aux_global_position" +
px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleGlobalPosition>(),
rclcpp::QoS(10).best_effort(), [this](px4_msgs::msg::VehicleGlobalPosition::UniquePtr msg) {
_update_msg = std::move(msg);
});
px4_ros2::getMessageNameVersion<px4_msgs::msg::AuxGlobalPosition>(),
rclcpp::QoS(10).best_effort(),
[this](px4_msgs::msg::AuxGlobalPosition::UniquePtr msg) { _update_msg = std::move(msg); });
}

bool waitForUpdate()
Expand All @@ -67,8 +66,8 @@ class GlobalPositionInterfaceTest : public testing::Test {
std::shared_ptr<rclcpp::Node> _node;
rclcpp::executors::SingleThreadedExecutor _executor;
std::shared_ptr<px4_ros2::GlobalPositionMeasurementInterface> _global_navigation_interface;
rclcpp::Subscription<px4_msgs::msg::VehicleGlobalPosition>::SharedPtr _subscriber;
px4_msgs::msg::VehicleGlobalPosition::UniquePtr _update_msg;
rclcpp::Subscription<px4_msgs::msg::AuxGlobalPosition>::SharedPtr _subscriber;
px4_msgs::msg::AuxGlobalPosition::UniquePtr _update_msg;

static constexpr std::chrono::seconds kTimeoutDuration{3s};
static constexpr std::chrono::milliseconds kSleepInterval{10ms};
Expand Down
Loading