Utility class with static helper functions for ROS handlers.
These functions are used by both main process and subprocess handlers. No IPC support needed - these are pure utility functions.
#include <ChROSHandlerUtilities.h>
|
| static builtin_interfaces::msg::Time | GetROSTimestamp (double elapsed_time_s) |
| | Convert Chrono simulation time to ROS timestamp Used when creating ROS message headers. More...
|
| |
| static double | GetChronoTime (const builtin_interfaces::msg::Time &time) |
| | Convert ROS timestamp to Chrono simulation time. More...
|
| |
| template<typename... Args> |
| static std::string | BuildRelativeTopicName (Args &&... args) |
| | Construct a relative topic name from path components Relative topic names start with "~/" and are resolved to the node namespace Example: BuildRelativeTopicName("sensing", "camera", "rgb") → "~/sensing/camera/rgb". More...
|
| |
| static bool | CheckROSTopicName (std::shared_ptr< ChROSInterface > interface, const std::string &topic_name) |
| | Validate that a topic name is valid according to ROS naming rules. More...
|
| |
◆ BuildRelativeTopicName()
template<typename... Args>
| static std::string chrono::ros::ChROSHandlerUtilities::BuildRelativeTopicName |
( |
Args &&... |
args | ) |
|
|
inlinestatic |
Construct a relative topic name from path components Relative topic names start with "~/" and are resolved to the node namespace Example: BuildRelativeTopicName("sensing", "camera", "rgb") → "~/sensing/camera/rgb".
- Parameters
-
| args | Variable number of path components |
- Returns
- Relative topic name string
◆ CheckROSTopicName()
| bool chrono::ros::ChROSHandlerUtilities::CheckROSTopicName |
( |
std::shared_ptr< ChROSInterface > |
interface, |
|
|
const std::string & |
topic_name |
|
) |
| |
|
static |
Validate that a topic name is valid according to ROS naming rules.
- Parameters
-
| interface | ROS interface with node context |
| topic_name | Topic name to validate |
- Returns
- true if valid, false otherwise
◆ GetChronoTime()
| double chrono::ros::ChROSHandlerUtilities::GetChronoTime |
( |
const builtin_interfaces::msg::Time & |
time | ) |
|
|
static |
Convert ROS timestamp to Chrono simulation time.
- Parameters
-
| time | ROS timestamp message |
- Returns
- Simulation time in seconds
◆ GetROSTimestamp()
| builtin_interfaces::msg::Time chrono::ros::ChROSHandlerUtilities::GetROSTimestamp |
( |
double |
elapsed_time_s | ) |
|
|
static |
Convert Chrono simulation time to ROS timestamp Used when creating ROS message headers.
- Parameters
-
| elapsed_time_s | Simulation time in seconds |
- Returns
- ROS timestamp message
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono_ros/handlers/ChROSHandlerUtilities.h
- /builds/uwsbel/chrono/src/chrono_ros/handlers/ChROSHandlerUtilities.cpp