chrono::ros::ChROSActuatorStateHandler Class Reference

Description

Publishes hydraulic actuator state to ROS.

Data flow: Callback → GetSerializedData() → IPC → Subprocess → ROS topic

Required companion files:

  • ChROSHydraulicCraneHandler_ipc.h (shared IPC struct)
  • ChROSActuatorStateHandler_ros.cpp (subprocess publisher)

#include <ChROSActuatorStateHandler.h>

Inheritance diagram for chrono::ros::ChROSActuatorStateHandler:
Collaboration diagram for chrono::ros::ChROSActuatorStateHandler:

Public Types

using StateCallback = std::function< ActuatorSnapshot()>
 Callback signature: returns a snapshot of the actuator state.
 
- Public Types inherited from chrono::ros::ChROSHandler
typedef chrono::ros::ipc::MessageType MessageType
 Get the message type of this handler. More...
 

Public Member Functions

 ChROSActuatorStateHandler (double update_rate, StateCallback callback, const std::string &topic_name="~/actuator/state")
 Construct an actuator state publisher. More...
 
virtual bool Initialize (std::shared_ptr< ChROSInterface > interface) override
 Initializes the handler. More...
 
virtual ipc::MessageType GetMessageType () const override
 
virtual std::vector< uint8_t > GetSerializedData (double time) override
 Get serialized data from this handler for IPC transmission. 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

- Protected Member Functions inherited from chrono::ros::ChROSHandler
 ChROSHandler (double update_rate)
 Constructor for the ChROSHandler 'update_rate' is the rate with which the handler should tick relative to the simulation clock. More...
 
void IncrementTickCount ()
 Increment the tick count.
 

Constructor & Destructor Documentation

◆ ChROSActuatorStateHandler()

chrono::ros::ChROSActuatorStateHandler::ChROSActuatorStateHandler ( double  update_rate,
StateCallback  callback,
const std::string &  topic_name = "~/actuator/state" 
)

Construct an actuator state publisher.

Parameters
update_ratePublishing rate in Hz (0 = every tick)
callbackLambda or function returning the actuator snapshot
topic_nameROS topic on which to publish the state

Member Function Documentation

◆ GetSerializedData()

std::vector< uint8_t > chrono::ros::ChROSActuatorStateHandler::GetSerializedData ( double  time)
overridevirtual

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. Returns serialized data as byte vector (empty if not supported).

Reimplemented from chrono::ros::ChROSHandler.

◆ Initialize()

bool chrono::ros::ChROSActuatorStateHandler::Initialize ( std::shared_ptr< ChROSInterface interface)
overridevirtual

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.

Implements chrono::ros::ChROSHandler.


The documentation for this class was generated from the following files:
  • /builds/uwsbel/chrono/src/chrono_ros/handlers/mbs/ChROSActuatorStateHandler.h
  • /builds/uwsbel/chrono/src/chrono_ros/handlers/mbs/ChROSActuatorStateHandler.cpp