class mola::BridgeROS2
Overview
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.
#include <BridgeROS2.h> class BridgeROS2: public mola::RawDataSourceBase, public mola::RawDataConsumer { public: // structs struct MolaSubs; struct Params; // methods virtual void spinOnce(); virtual void onNewObservation(const CObservation::ConstPtr& o); };
Inherited Members
public: // structs struct DiagnosticsOutput; struct SensorViewerImpl; // methods virtual void initialize(const Yaml& cfg) = 0; virtual void spinOnce() = 0; ExecutableBase& operator = (const ExecutableBase&); ExecutableBase& operator = (ExecutableBase&&); RawDataSourceBase& operator = (const RawDataSourceBase&); RawDataSourceBase& operator = (RawDataSourceBase&&);
Methods
virtual void spinOnce()
Runs any required action on a timely manner
virtual void onNewObservation(const CObservation::ConstPtr& o)
To be called whenever a new observation arrives. It should return as fast as possible, enqueuing the data for processing in another thread.