Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
fuse_models::Twist2D Class Reference

An adapter-type sensor that produces absolute velocity constraints from information published by another node. More...

#include <twist_2d.h>

Inheritance diagram for fuse_models::Twist2D:
Inheritance graph
[legend]

Public Types

using ParameterType = parameters::Twist2DParams
 

Public Member Functions

 FUSE_SMART_PTR_DEFINITIONS (Twist2D)
 
void process (const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg)
 Callback for twist messages. More...
 
 Twist2D ()
 Default constructor. More...
 
virtual ~Twist2D ()=default
 Destructor. More...
 
- Public Member Functions inherited from fuse_core::AsyncSensorModel
 FUSE_SMART_PTR_ALIASES_ONLY (AsyncSensorModel)
 
void graphCallback (Graph::ConstSharedPtr graph) override
 
void initialize (const std::string &name, TransactionCallback transaction_callback) override
 
const std::string & name () const override
 
void sendTransaction (Transaction::SharedPtr transaction)
 
void start () override
 
void stop () override
 
virtual ~AsyncSensorModel ()=default
 
- Public Member Functions inherited from fuse_core::SensorModel
 FUSE_SMART_PTR_ALIASES_ONLY (SensorModel)
 
virtual ~SensorModel ()=default
 

Protected Types

using TwistThrottledCallback = fuse_core::ThrottledMessageCallback< geometry_msgs::TwistWithCovarianceStamped >
 

Protected Member Functions

void onInit () override
 Loads ROS parameters and subscribes to the parameterized topic. More...
 
void onStart () override
 Subscribe to the input topic to start sending transactions to the optimizer. More...
 
void onStop () override
 Unsubscribe from the input topic to stop sending transactions to the optimizer. More...
 
- Protected Member Functions inherited from fuse_core::AsyncSensorModel
 AsyncSensorModel (size_t thread_count=1)
 
virtual void onGraphUpdate (Graph::ConstSharedPtr)
 
- Protected Member Functions inherited from fuse_core::SensorModel
 SensorModel ()=default
 

Protected Attributes

fuse_core::UUID device_id_
 The UUID of this device. More...
 
ParameterType params_
 
ros::Subscriber subscriber_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 
TwistThrottledCallback throttled_callback_
 
- Protected Attributes inherited from fuse_core::AsyncSensorModel
ros::CallbackQueue callback_queue_
 
std::string name_
 
ros::NodeHandle node_handle_
 
ros::NodeHandle private_node_handle_
 
ros::AsyncSpinner spinner_
 
TransactionCallback transaction_callback_
 

Detailed Description

An adapter-type sensor that produces absolute velocity constraints from information published by another node.

This sensor subscribes to a geometry_msgs::TwistWithCovarianceStamped topic and converts each received message into two absolute velocity constraints (one for linear velocity, and one for angular).

Parameters:

Subscribes:

Definition at line 66 of file twist_2d.h.

Member Typedef Documentation

◆ ParameterType

Definition at line 70 of file twist_2d.h.

◆ TwistThrottledCallback

using fuse_models::Twist2D::TwistThrottledCallback = fuse_core::ThrottledMessageCallback<geometry_msgs::TwistWithCovarianceStamped>
protected

Definition at line 114 of file twist_2d.h.

Constructor & Destructor Documentation

◆ Twist2D()

fuse_models::Twist2D::Twist2D ( )

Default constructor.

Definition at line 51 of file twist_2d.cpp.

◆ ~Twist2D()

virtual fuse_models::Twist2D::~Twist2D ( )
virtualdefault

Destructor.

Member Function Documentation

◆ FUSE_SMART_PTR_DEFINITIONS()

fuse_models::Twist2D::FUSE_SMART_PTR_DEFINITIONS ( Twist2D  )

◆ onInit()

void fuse_models::Twist2D::onInit ( )
overrideprotectedvirtual

Loads ROS parameters and subscribes to the parameterized topic.

Reimplemented from fuse_core::AsyncSensorModel.

Definition at line 59 of file twist_2d.cpp.

◆ onStart()

void fuse_models::Twist2D::onStart ( )
overrideprotectedvirtual

Subscribe to the input topic to start sending transactions to the optimizer.

Reimplemented from fuse_core::AsyncSensorModel.

Definition at line 77 of file twist_2d.cpp.

◆ onStop()

void fuse_models::Twist2D::onStop ( )
overrideprotectedvirtual

Unsubscribe from the input topic to stop sending transactions to the optimizer.

Reimplemented from fuse_core::AsyncSensorModel.

Definition at line 88 of file twist_2d.cpp.

◆ process()

void fuse_models::Twist2D::process ( const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &  msg)

Callback for twist messages.

Parameters
[in]msg- The twist message to process

Definition at line 93 of file twist_2d.cpp.

Member Data Documentation

◆ device_id_

fuse_core::UUID fuse_models::Twist2D::device_id_
protected

The UUID of this device.

Definition at line 89 of file twist_2d.h.

◆ params_

ParameterType fuse_models::Twist2D::params_
protected

Definition at line 106 of file twist_2d.h.

◆ subscriber_

ros::Subscriber fuse_models::Twist2D::subscriber_
protected

Definition at line 112 of file twist_2d.h.

◆ tf_buffer_

tf2_ros::Buffer fuse_models::Twist2D::tf_buffer_
protected

Definition at line 108 of file twist_2d.h.

◆ tf_listener_

tf2_ros::TransformListener fuse_models::Twist2D::tf_listener_
protected

Definition at line 110 of file twist_2d.h.

◆ throttled_callback_

TwistThrottledCallback fuse_models::Twist2D::throttled_callback_
protected

Definition at line 115 of file twist_2d.h.


The documentation for this class was generated from the following files:


fuse_models
Author(s): Tom Moore
autogenerated on Thu Apr 24 2025 02:19:08