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

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

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

Inheritance diagram for px4_ros2::GlobalPositionMeasurementInterface:
px4_ros2::PositionMeasurementInterfaceBase px4_ros2::Context

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
 

Detailed Description

Base class for a global position measurement provider.

Member Function Documentation

◆ reset()

void px4_ros2::GlobalPositionMeasurementInterface::reset ( )
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.

◆ update()

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:

  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.
    Parameters
    global_position_measurementThe global 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: