An adapter-type sensor that produces absolute velocity constraints from information published by another node. More...
#include <twist_2d.h>

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_ |
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:
topic (geometry_msgs::TwistWithCovarianceStamped) Absolute velocity information at a given timestamp Definition at line 66 of file twist_2d.h.
Definition at line 70 of file twist_2d.h.
|
protected |
Definition at line 114 of file twist_2d.h.
| fuse_models::Twist2D::Twist2D | ( | ) |
Default constructor.
Definition at line 51 of file twist_2d.cpp.
|
virtualdefault |
Destructor.
| fuse_models::Twist2D::FUSE_SMART_PTR_DEFINITIONS | ( | Twist2D | ) |
|
overrideprotectedvirtual |
Loads ROS parameters and subscribes to the parameterized topic.
Reimplemented from fuse_core::AsyncSensorModel.
Definition at line 59 of file twist_2d.cpp.
|
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.
|
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.
| void fuse_models::Twist2D::process | ( | const geometry_msgs::TwistWithCovarianceStamped::ConstPtr & | msg | ) |
Callback for twist messages.
| [in] | msg | - The twist message to process |
Definition at line 93 of file twist_2d.cpp.
|
protected |
The UUID of this device.
Definition at line 89 of file twist_2d.h.
|
protected |
Definition at line 106 of file twist_2d.h.
|
protected |
Definition at line 112 of file twist_2d.h.
|
protected |
Definition at line 108 of file twist_2d.h.
|
protected |
Definition at line 110 of file twist_2d.h.
|
protected |
Definition at line 115 of file twist_2d.h.