Base class for a global position measurement provider.
More...
#include <px4_ros2/navigation/experimental/global_position_measurement_interface.hpp>
|
| | GlobalPositionMeasurementInterface (rclcpp::Node &node, uint8_t id=1, GlobalPositionSource source=GlobalPositionSource::Vision, std::string topic_namespace_prefix="") |
| |
| 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:
|
| |
| void | reset () |
| | Notify the FMU that the global position estimate has been reset.
|
| |
|
| PositionMeasurementInterfaceBase (rclcpp::Node &node, std::string topic_namespace_prefix="") |
| |
| bool | doRegister () |
| |
|
| 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) |
| |
Base class for a global position measurement provider.
◆ GlobalPositionMeasurementInterface()
| px4_ros2::GlobalPositionMeasurementInterface::GlobalPositionMeasurementInterface |
( |
rclcpp::Node & |
node, |
|
|
uint8_t |
id = 1, |
|
|
GlobalPositionSource |
source = GlobalPositionSource::Vision, |
|
|
std::string |
topic_namespace_prefix = "" |
|
) |
| |
|
explicit |
- Parameters
-
| node | ROS node |
| id | Unique identifier non-zero for this position source. PX4 uses this to demultiplex measurements from multiple external positioning sources on the same topic. |
| source | Source type of the position data. Defaults to GlobalPositionSource::Vision. |
| topic_namespace_prefix | optional topic prefix |
◆ 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:
- The sample timestamp is defined.
- Values do not have a NAN.
- If a measurement value is provided, its associated variance value is well defined.
- Parameters
-
| global_position_measurement | The global position measurement to publish. |
- Exceptions
-
The documentation for this class was generated from the following file: