|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Base class for a local position measurement provider. More...
#include <px4_ros2/navigation/experimental/local_position_measurement_interface.hpp>
Public Member Functions | |
| LocalPositionMeasurementInterface (rclcpp::Node &node, PoseFrame pose_frame, VelocityFrame velocity_frame, std::string topic_namespace_prefix="") | |
| void | update (const LocalPositionMeasurement &local_position_measurement) const |
| Publishes a local position measurement to the FMU. Throws an exception if the following conditions are not met: 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 local position measurement provider.
| void px4_ros2::LocalPositionMeasurementInterface::update | ( | const LocalPositionMeasurement & | local_position_measurement | ) | const |
Publishes a local position measurement to the FMU. Throws an exception if the following conditions are not met:
| local_position_measurement | The local position measurement to publish. |
| px4_ros2::NavigationInterfaceInvalidArgument | if the conditions above are not met. |