Function fuse_models::common::processTwistWithCovariance

Function Documentation

inline bool fuse_models::common::processTwistWithCovariance(const std::string &source, const fuse_core::UUID &device_id, const geometry_msgs::msg::TwistWithCovarianceStamped &twist, const fuse_core::Loss::SharedPtr &linear_velocity_loss, const fuse_core::Loss::SharedPtr &angular_velocity_loss, const std::string &target_frame, const std::vector<size_t> &linear_indices, const std::vector<size_t> &angular_indices, const tf2_ros::Buffer &tf_buffer, const bool validate, fuse_core::Transaction &transaction, const rclcpp::Duration &tf_timeout = rclcpp::Duration(0, 0))

Extracts velocity data from a TwistWithCovarianceStamped and adds that data to a fuse Transaction.

This method effectively adds two variables (2D linear velocity and 2D angular velocity) and their respective constraints to the given transaction. The velocity data is extracted from the twist 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

  • twist[in] - The TwistWithCovarianceStamped message from which we will extract the twist data

  • linear_velocity_loss[in] - The loss function for the 2D linear velocity constraint generated

  • angular_velocity_loss[in] - The loss function for the 2D angular velocity constraint generated

  • target_frame[in] - The frame ID into which the twist 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