PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::LocalPositionMeasurementInterface Class Reference

Base class for a local position measurement provider. More...

#include <px4_ros2/navigation/experimental/local_position_measurement_interface.hpp>

Inheritance diagram for px4_ros2::LocalPositionMeasurementInterface:
px4_ros2::PositionMeasurementInterfaceBase px4_ros2::Context

Public Member Functions

 LocalPositionMeasurementInterface (rclcpp::Node &node, PoseFrame pose_frame, VelocityFrame velocity_frame)
 
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
 

Detailed Description

Base class for a local position measurement provider.

Member Function Documentation

◆ update()

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:

  1. The sample timestamp is defined.
  2. Values do not have a NAN.
  3. If a measurement value is provided, its associated variance value is well defined.
  4. If a measurement value is provided, its associated reference frame is not unknown.
    Parameters
    local_position_measurementThe local position measurement to publish.
    Exceptions
    px4_ros2::NavigationInterfaceInvalidArgumentif the conditions above are not met.

The documentation for this class was generated from the following file: