Class BridgeROS2
Defined in File BridgeROS2.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Types
public RawDataSourceBasepublic mola::RawDataConsumer
Class Documentation
-
class BridgeROS2 : public RawDataSourceBase, public mola::RawDataConsumer
A bridge to read sensor observations from ROS 2 topics and forwarding them to other MOLA subsystems, and to publish MOLA topics, localization, and maps to ROS 2.
Bridge ROS2=>MOLA
The MOLA nodelet execution rate (Hz) determines the rate of publishing odometry observations, if enabled. All other subscribed sensors are forwarded to the MOLA system without delay as they are received from ROS.
Bridge MOLA=>ROS2
Publish datasets from any of the MOLA dataset input modules to ROS 2.
Expose the results of a MOLA SLAM/odometry system to the rest of a ROS 2 system.
Every few seconds, this module will peek the MOLA subsystem for modules of these types, and subscribes to all their outputs:
mola::RawDataSourceBase: For all their sensor readings (as children classes of mrpt::obs::CObservation). See list of mappings below.
mola::LocalizationSourceBase: For SLAM/odometry method outputs.
mola::MapSourceBase: For SLAM/odometry metric maps. Point maps are published as sensor_msgs/PointCloud2
The following mappings are currently implemented between MOLA=>ROS2:
mrpt::obs::CObservation2DRangeScan ==> sensor_msgs/LaserScan
mrpt::obs::CObservationPointCloud ==> sensor_msgs/PointCloud2
mrpt::obs::CObservationImage ==> sensor_msgs/Image
mrpt::obs::CObservationRobotPose ==> nav_msgs/Odometry with frame_id=the robot (default:
base_link) and parent frame the global one (default:map, may make sense to change toodomdepending on your application). It will be also published as a transform to/tf.
For all sensors, the mrpt::obs::CObservation::sensorPose will be also broadcasted to
/tfwith respect to the vehicle frame (default:base_link).See example launch files in
mola_demosand inmola_lidar_odometry.Public Functions
-
BridgeROS2()
-
~BridgeROS2() override
-
BridgeROS2(const BridgeROS2&) = delete
-
BridgeROS2(BridgeROS2&&) = delete
-
BridgeROS2 &operator=(const BridgeROS2&) = delete
-
BridgeROS2 &operator=(BridgeROS2&&) = delete
-
void spinOnce() override
-
void onNewObservation(const CObservation::ConstPtr &o) override
Protected Functions
-
void initialize_rds(const Yaml &cfg) override