CreOS SDK
The CreOS SDK allows you to interact with Avular robots
 
Loading...
Searching...
No Matches
creos::ISensorsInterface Class Referenceabstract

The interface for retrieving sensor data from an Avular robot. More...

#include <creos/sensors_interface.hpp>

Public Member Functions

virtual SubscriptionId subscribeTo3dLidar (const creos_messages::Lidar3dId lidar_id, const std::function< void(const creos_messages::PointCloud2 &)> &callback)=0
 Subscribe to the lidar point cloud data.
 
virtual SubscriptionId subscribeToOdometry (const std::function< void(const creos_messages::Odometry &)> &callback)=0
 Subscribe to the odometry data.
 
virtual SubscriptionId subscribeToPose (const std::function< void(const creos_messages::PoseWithCovarianceStamped &)> &callback)=0
 Subscribe to the global pose data.
 
virtual SubscriptionId subscribeToGnss (const std::function< void(const creos_messages::Gnss &)> &callback)=0
 Subscribe to the GNSS data.
 
virtual SubscriptionId subscribeToRemoteController (const std::function< void(const creos_messages::ControllerState &)> &callback)=0
 Subscribe to the remote controller state data.
 
virtual SubscriptionId subscribeToWheelState (const std::function< void(const creos_messages::WheelStates &)> &callback)=0
 Subscribe to the wheel state data.
 
virtual SubscriptionId subscribeToMagneticField (creos_messages::MagneticFieldId magnetic_field_id, const std::function< void(const creos_messages::MagneticField &)> &callback)=0
 Subscribe to the magnetic field data.
 
virtual SubscriptionId subscribeToBarometer (const std::function< void(const creos_messages::Barometer &)> &callback)=0
 Subscribe to the barometer data.
 
virtual SubscriptionId subscribeToRangeSensor (creos_messages::RangeSensorId range_sensor_id, const std::function< void(const creos_messages::Range &)> &callback)=0
 Subscribe to range sensor data.
 
virtual SubscriptionId subscribeToImu (const creos_messages::ImuId imu_id, const std::function< void(const creos_messages::Imu &)> &callback)=0
 Subscribe to the IMU sensor data.
 

Static Public Attributes

static constexpr char name [] = "sensors"
 
static constexpr unsigned version = 1
 

Detailed Description

The interface for retrieving sensor data from an Avular robot.

Member Function Documentation

◆ subscribeTo3dLidar()

virtual SubscriptionId creos::ISensorsInterface::subscribeTo3dLidar ( const creos_messages::Lidar3dId lidar_id,
const std::function< void(const creos_messages::PointCloud2 &)> & callback )
pure virtualOrigin

Subscribe to the lidar point cloud data.

The point cloud is a 3D representation of the environment around the robot.

Parameters
lidar_idThe id of the lidar to subscribe to.
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide lidar point cloud data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToBarometer()

virtual SubscriptionId creos::ISensorsInterface::subscribeToBarometer ( const std::function< void(const creos_messages::Barometer &)> & callback)
pure virtualVertex

Subscribe to the barometer data.

The barometer data contains the atmospheric pressure and temperature around the robot.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide barometer data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToGnss()

virtual SubscriptionId creos::ISensorsInterface::subscribeToGnss ( const std::function< void(const creos_messages::Gnss &)> & callback)
pure virtualOriginVertex

Subscribe to the GNSS data.

The GNSS data contains the global position of the robot.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide GNSS data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToImu()

virtual SubscriptionId creos::ISensorsInterface::subscribeToImu ( const creos_messages::ImuId imu_id,
const std::function< void(const creos_messages::Imu &)> & callback )
pure virtualVertex

Subscribe to the IMU sensor data.

The IMU sensor data contains the acceleration, angular velocity and orientation of the robot.

Parameters
imu_idThe id of the IMU to subscribe to.
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide IMU sensor data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToMagneticField()

virtual SubscriptionId creos::ISensorsInterface::subscribeToMagneticField ( creos_messages::MagneticFieldId magnetic_field_id,
const std::function< void(const creos_messages::MagneticField &)> & callback )
pure virtualVertex

Subscribe to the magnetic field data.

The magnetic field data contains the magnetic field strength and direction around the robot.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide magnetic field data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToOdometry()

virtual SubscriptionId creos::ISensorsInterface::subscribeToOdometry ( const std::function< void(const creos_messages::Odometry &)> & callback)
pure virtualOrigin

Subscribe to the odometry data.

The odometry data contains the estimated position, orientation and velocity of the robot.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide odometry data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToPose()

virtual SubscriptionId creos::ISensorsInterface::subscribeToPose ( const std::function< void(const creos_messages::PoseWithCovarianceStamped &)> & callback)
pure virtualVertex

Subscribe to the global pose data.

The global pose data contains the estimated position and orientation of the robot in the global frame.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide global pose data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToRangeSensor()

virtual SubscriptionId creos::ISensorsInterface::subscribeToRangeSensor ( creos_messages::RangeSensorId range_sensor_id,
const std::function< void(const creos_messages::Range &)> & callback )
pure virtualVertex

Subscribe to range sensor data.

The range data contains the distance to an object in front of the sensor.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide downward lidar data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToRemoteController()

virtual SubscriptionId creos::ISensorsInterface::subscribeToRemoteController ( const std::function< void(const creos_messages::ControllerState &)> & callback)
pure virtualOriginVertex

Subscribe to the remote controller state data.

The remote controller state data contains the state of the buttons and joysticks of the remote controller.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide remote controller state data.
creos::SubscriptionErrorif the subscription failed.

◆ subscribeToWheelState()

virtual SubscriptionId creos::ISensorsInterface::subscribeToWheelState ( const std::function< void(const creos_messages::WheelStates &)> & callback)
pure virtualOrigin

Subscribe to the wheel state data.

Parameters
callbackThe callback function that will be called when new data is available.
Returns
SubscriptionId The id of the subscription.
Exceptions
creos::UnsupportedErrorif the robot does not provide wheel state data.
creos::SubscriptionErrorif the subscription failed.

The documentation for this class was generated from the following file: