chrono::ros Namespace Reference
Description
Namespace for Chrono::ROS.
Classes | |
| class | ChROSAccelerometerHandler |
| This handler is responsible for interfacing a ChAccelerometerSensor to ROS. Will publish sensor_msgs::msg::Imu. More... | |
| struct | ChROSBodyData |
| Data structure for body handler communication between processes. More... | |
| class | ChROSBodyHandler |
| Publishes pose, twist, and acceleration information for a ChBody. More... | |
| class | ChROSCameraHandler |
| Handler for publishing camera images to ROS via IPC communication. More... | |
| struct | ChROSClockData |
| Data structure for clock handler communication between processes. More... | |
| class | ChROSClockHandler |
| Publishes rosgraph_msgs::msg::Clock messages to synchronize ROS time with simulation time. More... | |
| class | ChROSDriverInputsHandler |
| Handler for interfacing a ChDriver to ROS via bidirectional IPC communication. More... | |
| class | ChROSGPSHandler |
| This handler is responsible for interfacing a ChGPSSensor to ROS. Will publish sensor_msgs::msg::NavSatFix. More... | |
| class | ChROSGyroscopeHandler |
| This handler is responsible for interfacing a ChGyroscopeSensor to ROS. Will publish sensor_msgs::msg::Imu. More... | |
| class | ChROSHandler |
| Base class for a ROS handler. More... | |
| class | ChROSHandlerRegistry |
| Registry for handler publishing functions in the subprocess. More... | |
| class | ChROSHandlerUtilities |
| Utility class with static helper functions for ROS handlers. More... | |
| class | ChROSInterface |
| This class handles the API interface between Chrono and ROS. More... | |
| class | ChROSIPCInterface |
| IPC-based interface that runs ROS in a separate process to avoid symbol conflicts. More... | |
| class | ChROSLidarHandler |
| Handler for publishing Lidar data to ROS via IPC communication. More... | |
| class | ChROSMagnetometerHandler |
| This handler is responsible for interfacing a ChMagnetometerSensor to ROS. More... | |
| class | ChROSManager |
| Manages the ROS handlers and their registration/updates. More... | |
| class | ChROSRobotModelHandler |
| This handler is responsible for publishing a robot model to be visualized in RViz RViz expects a string containing the robot model. More... | |
| class | ChROSSensorHandlerUtilities |
| Utility class with static functions that may be useful for sensor-specific ROS handlers. More... | |
| class | ChROSTFHandler |
| Handler responsible for publishing transform (tf) information via IPC. More... | |
| class | ChROSViperDCMotorControlHandler |
| This handler is responsible for interfacing a ViperDCMotorControl driver to ROS. More... | |
Enumerations | |
| enum | ChROSLidarHandlerMessageType { LASER_SCAN, POINT_CLOUD2 } |
Functions | |
| void | PublishBodyToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| ROS publishing function for body handler This is called in the subprocess when body data arrives via IPC. | |
| void | PublishClockToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| ROS publishing function for clock handler This is called in the subprocess when clock data arrives via IPC. | |
| geometry_msgs::msg::TransformStamped | CreateTransformStamped (chrono::ChFrame<> local_to_parent, const std::string &parent_frame_id, const std::string &child_frame_id, double time) |
| void | PublishTFToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| ROS publishing function for TF handler Receives variable-size array of transforms and publishes to /tf. | |
| void | PublishRobotModelToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | OnViperDCMotorControlReceived (const chrono_ros_interfaces::msg::ViperDCMotorControl::SharedPtr msg) |
| void | SetupViperDCMotorControlSubscriber (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| Setup function called by subprocess to create ROS subscriber. More... | |
| void | PublishAccelerometerToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | PublishCameraToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| ROS publishing function for camera handler This is called in the subprocess when camera data arrives via IPC. | |
| void | PublishGPSToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | PublishGyroscopeToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | PublishIMUToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | PublishLidarPointCloud (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | PublishLidarLaserScan (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | PublishMagnetometerToROS (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| void | OnDriverInputsReceived (const chrono_ros_interfaces::msg::DriverInputs::SharedPtr msg) |
| Callback when ROS message is received - sends via IPC back to main process. | |
| void | SetupDriverInputsSubscriber (const uint8_t *data, size_t data_size, rclcpp::Node::SharedPtr node, ipc::IPCChannel *channel) |
| Setup function called from subprocess dispatcher This creates the ROS subscriber and stores the IPC channel for sending back. | |
Function Documentation
◆ SetupViperDCMotorControlSubscriber()
| void chrono::ros::SetupViperDCMotorControlSubscriber | ( | const uint8_t * | data, |
| size_t | data_size, | ||
| rclcpp::Node::SharedPtr | node, | ||
| ipc::IPCChannel * | channel | ||
| ) |
Setup function called by subprocess to create ROS subscriber.
- Parameters
-
data Serialized topic name from main process data_size Size of data in bytes node ROS node to create subscriber on