Class Acceleration2D
Defined in File acceleration_2d.hpp
Inheritance Relationships
Base Type
public fuse_core::AsyncSensorModel
Class Documentation
-
class Acceleration2D : public fuse_core::AsyncSensorModel
An adapter-type sensor that produces 2D linear acceleration constraints from information published by another node.
This sensor subscribes to a geometry_msgs::msg::AccelWithCovarianceStamped topic and converts each received message into a 2D linear acceleration variable and constraint.
Parameters:
device_id (uuid string, default: 00000000-0000-0000-0000-000000000000) The device/robot ID to publish
device_name (string) Used to generate the device/robot ID if the device_id is not provided
queue_size (int, default: 10) The subscriber queue size for the twist messages
target_frame (string) The target frame_id to transform the data into before using it
topic (string) The topic to which to subscribe for the twist messages
Subscribes:
topic
(geometry_msgs::msg::AccelWithCovarianceStamped) Acceleration information at a given timestamp
Public Types
-
using ParameterType = parameters::Acceleration2DParams
Public Functions
-
Acceleration2D()
Default constructor.
-
virtual ~Acceleration2D() = default
Destructor.
-
void initialize(fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces, const std::string &name, fuse_core::TransactionCallback transaction_callback) override
Shadowing extension to the AsyncSensorModel::initialize call.
-
void process(const geometry_msgs::msg::AccelWithCovarianceStamped &msg)
Callback for acceleration messages.
- Parameters:
msg – [in] - The acceleration message to process
Protected Types
-
using AccelerationThrottledCallback = fuse_core::ThrottledMessageCallback<geometry_msgs::msg::AccelWithCovarianceStamped>
Protected Functions
-
void onInit() override
Perform any required initialization for the sensor model.
This could include things like reading from the parameter server or subscribing to topics. The class’s node handles will be properly initialized before SensorModel::onInit() is called. Spinning of the callback queue will not begin until after the call to SensorModel::onInit() completes.
-
void onStart() override
Subscribe to the input topic to start sending transactions to the optimizer.
-
void onStop() override
Unsubscribe from the input topic to stop sending transactions to the optimizer.
Protected Attributes
-
fuse_core::UUID device_id_
The UUID of this device.
-
fuse_core::node_interfaces::NodeInterfaces<fuse_core::node_interfaces::Base, fuse_core::node_interfaces::Clock, fuse_core::node_interfaces::Logging, fuse_core::node_interfaces::Parameters, fuse_core::node_interfaces::Topics, fuse_core::node_interfaces::Waitables> interfaces_
Shadows AsyncSensorModel interfaces_.
-
rclcpp::Clock::SharedPtr clock_
The sensor model’s clock, for timestamping and logging.
-
rclcpp::Logger logger_
The sensor model’s logger.
-
ParameterType params_
-
std::unique_ptr<tf2_ros::Buffer> tf_buffer_
-
std::unique_ptr<tf2_ros::TransformListener> tf_listener_
-
rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr sub_
-
AccelerationThrottledCallback throttled_callback_