Struct Odometry2DPublisherParams
Defined in File odometry_2d_publisher_params.hpp
Inheritance Relationships
Base Type
public fuse_models::parameters::ParameterBase
(Struct ParameterBase)
Struct Documentation
-
struct Odometry2DPublisherParams : public fuse_models::parameters::ParameterBase
Defines the set of parameters required by the Odometry2DPublisher class.
Public Functions
- inline virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW void loadFromROS (fuse_core::node_interfaces::NodeInterfaces< fuse_core::node_interfaces::Base, fuse_core::node_interfaces::Logging, fuse_core::node_interfaces::Parameters > interfaces, const std::string &ns)
Method for loading parameter values from ROS.
- Parameters:
interfaces – [in] - The node interfaces with which to load parameters
ns – [in] - The parameter namespace to use
Public Members
-
bool publish_tf = {true}
Whether to publish/broadcast the TF transform or not.
-
bool invert_tf = {false}
Whether to broadcast the inverse of the TF transform or not. When the inverse is broadcasted, the transform is inverted and the header.frame_id and child_frame_id are swapped, i.e. the odometry output header.frame_id is set to the base_link_output_frame_id and the child_frame_id to the world_frame_id
-
bool predict_to_current_time = {false}
-
bool predict_with_acceleration = {false}
-
double publish_frequency = {10.0}
-
fuse_core::Matrix8d process_noise_covariance
Process noise covariance matrix.
-
bool scale_process_noise = {false}
-
double velocity_norm_min = {1e-3}
-
rclcpp::Duration covariance_throttle_period = {0, 0}
The throttle period duration in seconds to compute the covariance
-
rclcpp::Duration tf_cache_time = {10, 0}
-
rclcpp::Duration tf_timeout = {0, static_cast<uint32_t>(RCUTILS_S_TO_NS(0.1))}
-
int queue_size = {1}
-
std::string map_frame_id = {"map"}
-
std::string odom_frame_id = {"odom"}
-
std::string base_link_frame_id = {"base_link"}
-
std::string base_link_output_frame_id = {base_link_frame_id}
-
std::string world_frame_id = {odom_frame_id}
-
std::string topic = {"odometry/filtered"}
-
std::string acceleration_topic = {"acceleration/filtered"}
-
ceres::Covariance::Options covariance_options