Description
Handler for publishing camera images to ROS via IPC communication.
PUBLISHER PATTERN (Chrono → ROS):
- Main process: Extracts RGBA8 image data from ChCameraSensor
- Main process: Serializes metadata + pixel data into byte vector
- Subprocess: Deserializes and publishes as sensor_msgs::msg::Image
Data flow: ChCameraSensor → Main process → IPC → Subprocess → ROS topic
Implementation files:
- ChROSCameraHandler.cpp: Main process logic (extract and serialize)
- ChROSCameraHandler_ros.cpp: Subprocess ROS publisher
- ChROSCameraHandler_ipc.h: IPC data structure definition
To implement a similar sensor publisher:
- Create IPC struct in _ipc.h with sensor metadata (plain C++ types)
- In handler.cpp: Extract sensor data in GetSerializedData()
- Serialize metadata + raw data to byte vector
- In _ros.cpp: Deserialize, create ROS message, publish
- Register with CHRONO_ROS_REGISTER_HANDLER macro
- Add message type to ChROSIPCMessage.h enum
- Add handler recognition to ChROSManager::GetHandlerMessageType()
#include <ChROSCameraHandler.h>


Public Member Functions | |
| ChROSCameraHandler (std::shared_ptr< chrono::sensor::ChCameraSensor > camera, const std::string &topic_name) | |
| Constructor with automatic update rate from sensor. | |
| ChROSCameraHandler (double update_rate, std::shared_ptr< chrono::sensor::ChCameraSensor > camera, const std::string &topic_name) | |
| Constructor with custom update rate. | |
| virtual bool | Initialize (std::shared_ptr< ChROSInterface > interface) override |
| Initialize handler (called once at startup in main process) In IPC mode, validates sensor has required filter, but doesn't create ROS publisher Subprocess will create the actual ROS publisher. | |
| virtual ipc::MessageType | GetMessageType () const override |
| Get the message type of this handler. | |
| virtual std::vector< uint8_t > | GetSerializedData (double time) override |
| Extract and serialize camera image data for IPC transmission Called in main process at update_rate frequency Returns metadata + pixel data as byte vector. | |
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. | |
| virtual void | PublishFromSerialized (const std::vector< uint8_t > &data, std::shared_ptr< ChROSInterface > interface) |
| Publish data to ROS from serialized bytes. | |
| virtual void | ApplyFromSerialized (const std::vector< uint8_t > &data) |
| Apply data to Chrono from serialized bytes. | |
| 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. | |
| virtual void | HandleIncomingMessage (const ipc::Message &msg) |
| Handle incoming IPC message from ROS subscriber (bidirectional communication). | |
| virtual bool | SupportsIncomingMessages () const |
| Returns true if this handler processes incoming IPC messages. | |
Additional Inherited Members | |
Public Types inherited from chrono::ros::ChROSHandler | |
| typedef chrono::ros::ipc::MessageType | MessageType |
| Get the message type of this handler. | |
Protected Member Functions inherited from chrono::ros::ChROSHandler | |
| ChROSHandler (double update_rate) | |
| Constructor for the ChROSHandler. | |
| void | IncrementTickCount () |
| Increment the tick count. | |
Constructor & Destructor Documentation
◆ ChROSCameraHandler() [1/2]
| chrono::ros::ChROSCameraHandler::ChROSCameraHandler | ( | std::shared_ptr< chrono::sensor::ChCameraSensor > | camera, |
| const std::string & | topic_name | ||
| ) |
Constructor with automatic update rate from sensor.
- Parameters
-
camera Camera sensor to publish data from topic_name ROS topic to publish images to
◆ ChROSCameraHandler() [2/2]
| chrono::ros::ChROSCameraHandler::ChROSCameraHandler | ( | double | update_rate, |
| std::shared_ptr< chrono::sensor::ChCameraSensor > | camera, | ||
| const std::string & | topic_name | ||
| ) |
Constructor with custom update rate.
- Parameters
-
update_rate Rate at which to publish images (Hz) camera Camera sensor to publish data from topic_name ROS topic to publish images to
Member Function Documentation
◆ GetMessageType()
|
inlineoverridevirtual |
Get the message type of this handler.
Reimplemented from chrono::ros::ChROSHandler.
◆ GetSerializedData()
|
overridevirtual |
Extract and serialize camera image data for IPC transmission Called in main process at update_rate frequency Returns metadata + pixel data as byte vector.
- Parameters
-
time Current simulation time
- Returns
- Serialized camera data (header + RGBA8 pixels)
Reimplemented from chrono::ros::ChROSHandler.
◆ Initialize()
|
overridevirtual |
Initialize handler (called once at startup in main process) In IPC mode, validates sensor has required filter, but doesn't create ROS publisher Subprocess will create the actual ROS publisher.
Implements chrono::ros::ChROSHandler.
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono_ros/handlers/sensor/ChROSCameraHandler.h
- /builds/uwsbel/chrono/src/chrono_ros/handlers/sensor/ChROSCameraHandler.cpp
Public Member Functions inherited from