chrono::ros::ChROSClockHandler Class Reference
Description
Publishes rosgraph_msgs::msg::Clock messages to synchronize ROS time with simulation time.
PUBLISHER PATTERN:
- Main process: Calls GetSerializedData() each tick → sends IPC
- Subprocess: Receives IPC → calls registered function → publishes ROS message
Implementation files:
- ChROSClockHandler.cpp: Main process logic (this handler, Tick not used in IPC mode)
- ChROSClockHandler_ros.cpp: Subprocess ROS publishing (compiled into chrono_ros_node)
To implement a similar publisher handler:
- Define IPC struct above (plain C++ types)
- Implement GetSerializedData() to pack your data
- Create YourHandler_ros.cpp with publishing function
- Register with CHRONO_ROS_REGISTER_HANDLER(YOUR_MESSAGE_TYPE, YourPublishFunction)
- Add YOUR_MESSAGE_TYPE to MessageType enum in ChROSIPCMessage.h
- Add handler recognition to ChROSManager::GetHandlerMessageType()
#include <ChROSClockHandler.h>
Inheritance diagram for chrono::ros::ChROSClockHandler:

Collaboration diagram for chrono::ros::ChROSClockHandler:

Public Member Functions | |
| ChROSClockHandler (double update_rate=0, const std::string &topic_name="/clock") | |
| virtual bool | Initialize (std::shared_ptr< ChROSInterface > interface) override |
| Initialize handler (called once at startup in main process) In IPC mode, this does nothing since ROS node is in subprocess. | |
| virtual ipc::MessageType | GetMessageType () const override |
| Get the message type of this handler. | |
| virtual std::vector< uint8_t > | GetSerializedData (double time) override |
| Extract simulation time for IPC transmission to subprocess Called each tick in main process. More... | |
Public Member Functions inherited from chrono::ros::ChROSHandler | |
| virtual | ~ChROSHandler ()=default |
| Destructor for the ChROSHandler. | |
| 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 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... | |
Additional Inherited Members | |
Public Types inherited from chrono::ros::ChROSHandler | |
| typedef chrono::ros::ipc::MessageType | MessageType |
| Get the message type of this handler. More... | |
Protected Member Functions inherited from chrono::ros::ChROSHandler | |
| ChROSHandler (double update_rate) | |
| Constructor for the ChROSHandler. More... | |
| void | IncrementTickCount () |
| Increment the tick count. | |
Member Function Documentation
◆ GetSerializedData()
|
overridevirtual |
Extract simulation time for IPC transmission to subprocess Called each tick in main process.
Packs ChROSClockData struct into byte vector. Subprocess receives this data and publishes ROS message.
- Parameters
-
time Current simulation time in seconds
- Returns
- Serialized ChROSClockData as byte vector
Reimplemented from chrono::ros::ChROSHandler.
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono_ros/handlers/ChROSClockHandler.h
- /builds/uwsbel/chrono/src/chrono_ros/handlers/ChROSClockHandler.cpp
Public Member Functions inherited from