Struct Imu2DParams
Defined in File imu_2d_params.hpp
Inheritance Relationships
Base Type
public fuse_models::parameters::ParameterBase
(Struct ParameterBase)
Struct Documentation
-
struct Imu2DParams : public fuse_models::parameters::ParameterBase
Defines the set of parameters required by the Imu2D class.
Public Functions
-
inline virtual 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 differential = {false}
-
bool disable_checks = {false}
-
bool independent = {true}
-
bool use_twist_covariance = {true}
-
fuse_core::Matrix3d minimum_pose_relative_covariance
Minimum pose relative covariance matrix
-
fuse_core::Matrix3d twist_covariance_offset
Offset already added to the twist covariance matrix, that will be substracted in order to recover the raw values
-
bool remove_gravitational_acceleration = {false}
-
int queue_size = {10}
-
rclcpp::Duration tf_timeout = {0, 0}
The maximum time to wait for a transform to become available
-
rclcpp::Duration throttle_period = {0, 0}
The throttle period duration in seconds.
-
bool throttle_use_wall_time = {false}
Whether to throttle using ros::WallTime or not.
-
double gravitational_acceleration = {9.80665}
-
std::string acceleration_target_frame = {}
-
std::string orientation_target_frame = {}
-
std::string topic = {}
-
std::string twist_target_frame = {}
-
std::vector<size_t> angular_velocity_indices
-
std::vector<size_t> linear_acceleration_indices
-
std::vector<size_t> orientation_indices
-
fuse_core::Loss::SharedPtr pose_loss
-
fuse_core::Loss::SharedPtr angular_velocity_loss
-
fuse_core::Loss::SharedPtr linear_acceleration_loss
-
inline virtual 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)