Description
Base class for a ROS handler.
A specific handler should inherit from here. A handler is essentially a wrapper around a ROS subscriber/publisher/service/action.
IMPORTANT: To support IPC communication while avoiding VSG symbol collisions, handlers should be split into two logical parts:
- Data extraction from Chrono (runs in main process, NO ROS symbols)
- ROS publishing/subscribing (runs in subprocess or direct mode, full ROS API)
This split is transparent to the handler implementation - the framework automatically handles serialization and IPC when needed. Handlers define a data struct and implement methods to extract/apply data and publish/subscribe.
#include <ChROSHandler.h>

Public Types | |
| typedef chrono::ros::ipc::MessageType | MessageType |
| Get the message type of this handler. More... | |
Public Member Functions | |
| virtual | ~ChROSHandler ()=default |
| Destructor for the ChROSHandler. | |
| virtual bool | Initialize (std::shared_ptr< ChROSInterface > interface)=0 |
| Initializes the handler. More... | |
| const double | GetUpdateRate () const |
| Get the period which this handler operates at. | |
| const uint64_t | GetTickCount () const |
| Get the number of times Tick() has been called. | |
| virtual bool | IsPublisher () const |
| Check if this handler is a publisher (data flows from Chrono to ROS) Default is true. More... | |
| virtual chrono::ros::ipc::MessageType | GetMessageType () const |
| virtual std::vector< uint8_t > | GetSerializedData (double time) |
| Get serialized data from this handler for IPC transmission. More... | |
| virtual void | PublishFromSerialized (const std::vector< uint8_t > &data, std::shared_ptr< ChROSInterface > interface) |
| Publish data to ROS from serialized bytes. More... | |
| virtual void | ApplyFromSerialized (const std::vector< uint8_t > &data) |
| Apply data to Chrono from serialized bytes. More... | |
| virtual void | SubscribeAndForward (std::shared_ptr< ChROSInterface > interface, std::function< void(const std::vector< uint8_t > &)> callback) |
| Setup subscriber in subprocess to send data back to main process. More... | |
| virtual void | HandleIncomingMessage (const ipc::Message &msg) |
| Handle incoming IPC message from ROS subscriber (bidirectional communication). More... | |
| virtual bool | SupportsIncomingMessages () const |
| Returns true if this handler processes incoming IPC messages. More... | |
Protected Member Functions | |
| ChROSHandler (double update_rate) | |
| Constructor for the ChROSHandler. More... | |
| void | IncrementTickCount () |
| Increment the tick count. | |
Member Typedef Documentation
◆ MessageType
| typedef chrono::ros::ipc::MessageType chrono::ros::ChROSHandler::MessageType |
Get the message type of this handler.
Must be implemented by derived classes to identify the IPC message type.
- Returns
- The IPC message type for this handler
Constructor & Destructor Documentation
◆ ChROSHandler()
|
explicitprotected |
Constructor for the ChROSHandler.
- Parameters
-
update_rate Update rate with which the handler should tick relative to the simulation clock. NOTE: A update_rate of 0 indicates tick should be called on each update of the simulation.
Member Function Documentation
◆ ApplyFromSerialized()
|
inlinevirtual |
Apply data to Chrono from serialized bytes.
Framework calls this in main process for subscribers. Handler should deserialize and apply to Chrono objects. Default implementation does nothing for backward compatibility.
- Parameters
-
data Serialized data bytes
◆ GetSerializedData()
|
inlinevirtual |
Get serialized data from this handler for IPC transmission.
Framework calls this in main process for publishers. Handler should extract Chrono data and return as byte vector. Default implementation calls Tick() for backward compatibility.
- Parameters
-
time Current simulation time
- Returns
- Serialized data as byte vector (empty if not supported)
Reimplemented in chrono::ros::ChROSDriverInputsHandler, chrono::ros::ChROSClockHandler, chrono::ros::ChROSCameraHandler, chrono::ros::ChROSTFHandler, chrono::ros::ChROSLidarHandler, chrono::ros::ChROSBodyHandler, chrono::ros::ChROSViperDCMotorControlHandler, chrono::ros::ChROSRobotModelHandler, chrono::ros::ChROSAccelerometerHandler, chrono::ros::ChROSGyroscopeHandler, chrono::ros::ChROSMagnetometerHandler, and chrono::ros::ChROSGPSHandler.
◆ HandleIncomingMessage()
|
inlinevirtual |
Handle incoming IPC message from ROS subscriber (bidirectional communication).
Override this in handlers that receive data from ROS via IPC. Base implementation does nothing - only bidirectional subscribers override this.
- Parameters
-
msg The incoming IPC message to process
Reimplemented in chrono::ros::ChROSDriverInputsHandler, and chrono::ros::ChROSViperDCMotorControlHandler.
◆ Initialize()
|
pure virtual |
Initializes the handler.
Must be implemented by derived classes. This is called after rclcpp::init(). In IPC mode, this is only called in the subprocess. In direct mode, called in main process. Here the underlying ROS objects (e.g. publisher, subscription) should be created.
- Parameters
-
interface The interface to the ROS node
Implemented in chrono::ros::ChROSDriverInputsHandler, chrono::ros::ChROSClockHandler, chrono::ros::ChROSCameraHandler, chrono::ros::ChROSLidarHandler, chrono::ros::ChROSTFHandler, chrono::ros::ChROSBodyHandler, chrono::ros::ChROSRobotModelHandler, chrono::ros::ChROSAccelerometerHandler, chrono::ros::ChROSGyroscopeHandler, chrono::ros::ChROSMagnetometerHandler, chrono::ros::ChROSViperDCMotorControlHandler, and chrono::ros::ChROSGPSHandler.
◆ IsPublisher()
|
inlinevirtual |
Check if this handler is a publisher (data flows from Chrono to ROS) Default is true.
Override to false for subscribers.
◆ PublishFromSerialized()
|
inlinevirtual |
Publish data to ROS from serialized bytes.
Framework calls this in subprocess (or direct mode) for publishers. Handler should deserialize and publish to ROS topics. Default implementation does nothing for backward compatibility.
- Parameters
-
data Serialized data bytes interface ROS interface to use for publishing
Reimplemented in chrono::ros::ChROSBodyHandler.
◆ SubscribeAndForward()
|
inlinevirtual |
Setup subscriber in subprocess to send data back to main process.
Framework calls this in subprocess for subscribers. Handler should create ROS subscription and call callback with serialized data. Default implementation does nothing for backward compatibility.
- Parameters
-
interface ROS interface to use for subscribing callback Function to call with serialized data when ROS message arrives
◆ SupportsIncomingMessages()
|
inlinevirtual |
Returns true if this handler processes incoming IPC messages.
Override to return true in bidirectional subscriber handlers.
Reimplemented in chrono::ros::ChROSDriverInputsHandler, and chrono::ros::ChROSViperDCMotorControlHandler.
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono_ros/ChROSHandler.h
- /builds/uwsbel/chrono/src/chrono_ros/ChROSHandler.cpp