Defines the set of parameters required by the Imu2D class. More...
#include <imu_2d_params.h>

Public Member Functions | |
| void | loadFromROS (const ros::NodeHandle &nh) final |
| Method for loading parameter values from ROS. More... | |
Public Member Functions inherited from fuse_models::parameters::ParameterBase | |
| ParameterBase ()=default | |
| virtual | ~ParameterBase ()=default |
Public Attributes | |
| std::string | acceleration_target_frame {} |
| std::vector< size_t > | angular_velocity_indices |
| fuse_core::Loss::SharedPtr | angular_velocity_loss |
| bool | differential { false } |
| bool | disable_checks { false } |
| double | gravitational_acceleration { 9.80665 } |
| bool | independent { true } |
| std::vector< size_t > | linear_acceleration_indices |
| fuse_core::Loss::SharedPtr | linear_acceleration_loss |
| fuse_core::Matrix3d | minimum_pose_relative_covariance |
| Minimum pose relative covariance matrix. More... | |
| std::vector< size_t > | orientation_indices |
| std::string | orientation_target_frame {} |
| fuse_core::Loss::SharedPtr | pose_loss |
| int | queue_size { 10 } |
| bool | remove_gravitational_acceleration { false } |
| bool | tcp_no_delay { false } |
| ros::Duration | tf_timeout { 0.0 } |
| The maximum time to wait for a transform to become available. More... | |
| ros::Duration | throttle_period { 0.0 } |
| The throttle period duration in seconds. More... | |
| bool | throttle_use_wall_time { false } |
| Whether to throttle using ros::WallTime or not. More... | |
| std::string | topic {} |
| fuse_core::Matrix3d | twist_covariance_offset |
| std::string | twist_target_frame {} |
| bool | use_twist_covariance { true } |
Defines the set of parameters required by the Imu2D class.
Definition at line 59 of file imu_2d_params.h.
|
inlinefinalvirtual |
Method for loading parameter values from ROS.
| [in] | nh | - The ROS node handle with which to load parameters |
Implements fuse_models::parameters::ParameterBase.
Definition at line 67 of file imu_2d_params.h.
| std::string fuse_models::parameters::Imu2DParams::acceleration_target_frame {} |
Definition at line 126 of file imu_2d_params.h.
| std::vector<size_t> fuse_models::parameters::Imu2DParams::angular_velocity_indices |
Definition at line 130 of file imu_2d_params.h.
| fuse_core::Loss::SharedPtr fuse_models::parameters::Imu2DParams::angular_velocity_loss |
Definition at line 134 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::differential { false } |
Definition at line 108 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::disable_checks { false } |
Definition at line 109 of file imu_2d_params.h.
| double fuse_models::parameters::Imu2DParams::gravitational_acceleration { 9.80665 } |
Definition at line 125 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::independent { true } |
Definition at line 110 of file imu_2d_params.h.
| std::vector<size_t> fuse_models::parameters::Imu2DParams::linear_acceleration_indices |
Definition at line 131 of file imu_2d_params.h.
| fuse_core::Loss::SharedPtr fuse_models::parameters::Imu2DParams::linear_acceleration_loss |
Definition at line 135 of file imu_2d_params.h.
| fuse_core::Matrix3d fuse_models::parameters::Imu2DParams::minimum_pose_relative_covariance |
Minimum pose relative covariance matrix.
Definition at line 112 of file imu_2d_params.h.
| std::vector<size_t> fuse_models::parameters::Imu2DParams::orientation_indices |
Definition at line 132 of file imu_2d_params.h.
| std::string fuse_models::parameters::Imu2DParams::orientation_target_frame {} |
Definition at line 127 of file imu_2d_params.h.
| fuse_core::Loss::SharedPtr fuse_models::parameters::Imu2DParams::pose_loss |
Definition at line 133 of file imu_2d_params.h.
| int fuse_models::parameters::Imu2DParams::queue_size { 10 } |
Definition at line 116 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::remove_gravitational_acceleration { false } |
Definition at line 115 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::tcp_no_delay { false } |
Whether to use TCP_NODELAY, i.e. disable Nagle's algorithm, in the subscriber socket or not. TCP_NODELAY forces a socket to send the data in its buffer, whatever the packet size. This reduces delay at the cost of network congestion, specially if the payload of a packet is smaller than the TCP header data. This is true for small ROS messages like geometry_msgs::AccelWithCovarianceStamped
Definition at line 117 of file imu_2d_params.h.
| ros::Duration fuse_models::parameters::Imu2DParams::tf_timeout { 0.0 } |
The maximum time to wait for a transform to become available.
Definition at line 122 of file imu_2d_params.h.
| ros::Duration fuse_models::parameters::Imu2DParams::throttle_period { 0.0 } |
The throttle period duration in seconds.
Definition at line 123 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::throttle_use_wall_time { false } |
Whether to throttle using ros::WallTime or not.
Definition at line 124 of file imu_2d_params.h.
| std::string fuse_models::parameters::Imu2DParams::topic {} |
Definition at line 128 of file imu_2d_params.h.
| fuse_core::Matrix3d fuse_models::parameters::Imu2DParams::twist_covariance_offset |
Offset already added to the twist covariance matrix, that will be substracted in order to recover the raw values
Definition at line 113 of file imu_2d_params.h.
| std::string fuse_models::parameters::Imu2DParams::twist_target_frame {} |
Definition at line 129 of file imu_2d_params.h.
| bool fuse_models::parameters::Imu2DParams::use_twist_covariance { true } |
Definition at line 111 of file imu_2d_params.h.