PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Base class for a global position measurement provider. More...
#include <px4_ros2/navigation/experimental/global_position_measurement_interface.hpp>
Public Member Functions | |
GlobalPositionMeasurementInterface (rclcpp::Node &node) | |
void | update (const GlobalPositionMeasurement &global_position_measurement) const |
Publishes a global position measurement to the FMU. Throws an exception if the following conditions are not met: More... | |
void | reset () |
Notify the FMU that the global position estimate has been reset. More... | |
Public Member Functions inherited from px4_ros2::PositionMeasurementInterfaceBase | |
PositionMeasurementInterfaceBase (rclcpp::Node &node, std::string topic_namespace_prefix="") | |
bool | doRegister () |
Public Member Functions inherited from px4_ros2::Context | |
Context (rclcpp::Node &node, std::string topic_namespace_prefix="") | |
rclcpp::Node & | node () |
const std::string & | topicNamespacePrefix () const |
virtual void | addSetpointType (SetpointBase *setpoint) |
virtual void | setRequirement (const RequirementFlags &requirement_flags) |
Additional Inherited Members | |
Protected Attributes inherited from px4_ros2::PositionMeasurementInterfaceBase | |
rclcpp::Node & | _node |
Base class for a global position measurement provider.
|
inline |
Notify the FMU that the global position estimate has been reset.
Increments the reset counter for horizontal position (latitude and longitude) to signal the EKF of a discontinuity in external position data (e.g., loss of tracking or reinitialization). Future measurement updates will contain the incremented counter. This prevents the EKF from rejecting future measurement updates after an inconsistency in data.
void px4_ros2::GlobalPositionMeasurementInterface::update | ( | const GlobalPositionMeasurement & | global_position_measurement | ) | const |
Publishes a global position measurement to the FMU. Throws an exception if the following conditions are not met:
global_position_measurement | The global position measurement to publish. |
px4_ros2::NavigationInterfaceInvalidArgument | if the conditions above are not met. |