Function fuse_models::common::processAbsolutePoseWithCovariance

Function Documentation

inline bool fuse_models::common::processAbsolutePoseWithCovariance(const std::string &source, const fuse_core::UUID &device_id, const geometry_msgs::msg::PoseWithCovarianceStamped &pose, const fuse_core::Loss::SharedPtr &loss, const std::string &target_frame, const std::vector<size_t> &position_indices, const std::vector<size_t> &orientation_indices, const tf2_ros::Buffer &tf_buffer, const bool validate, fuse_core::Transaction &transaction, const rclcpp::Duration &tf_timeout = rclcpp::Duration(0, 0))

Extracts 2D pose data from a PoseWithCovarianceStamped message and adds that data to a fuse Transaction.

This method effectively adds two variables (2D position and 2D orientation) and a 2D pose constraint to the given transaction. The pose data is extracted from the pose message. Only 2D data is used. The data will be automatically transformed into the target_frame before it is used.

Parameters:
  • source[in] - The name of the sensor or motion model that generated this constraint

  • device_id[in] - The UUID of the machine

  • pose[in] - The PoseWithCovarianceStamped message from which we will extract the pose data

  • loss[in] - The loss function for the 2D pose constraint generated

  • target_frame[in] - The frame ID into which the pose data will be transformed before it is used

  • tf_buffer[in] - The transform buffer with which we will lookup the required transform

  • validate[in] - Whether to validate the measurements or not. If the validation fails no constraint is added

  • transaction[out] - The generated variables and constraints are added to this transaction

Returns:

true if any constraints were added, false otherwise