Information about an SDF sensor. More...
#include <Sensor.hh>
Public Member Functions | |
Sensor () | |
Default constructor. More... | |
void | AddPlugin (const Plugin &_plugin) |
Add a plugin to this object. More... | |
AirPressure * | AirPressureSensor () |
Get a mutable air pressure sensor, or nullptr if this sensor type is not an AirPressure sensor. More... | |
const AirPressure * | AirPressureSensor () const |
Get the air pressure sensor, or nullptr if this sensor type is not an AirPressure sensor. More... | |
AirSpeed * | AirSpeedSensor () |
Get a mutable air speed sensor, or nullptr if this sensor type is not an AirSpeed sensor. More... | |
const AirSpeed * | AirSpeedSensor () const |
Get the air speed sensor, or nullptr if this sensor type is not an AirSpeed sensor. More... | |
Altimeter * | AltimeterSensor () |
Get a mutable altimeter sensor, or nullptr if this sensor type is not an Altimeter. More... | |
const Altimeter * | AltimeterSensor () const |
Get the altimeter sensor, or nullptr if this sensor type is not an Altimeter. More... | |
Camera * | CameraSensor () |
Get a mutable camera sensor, or nullptr if the sensor does not contain a camera sensor. More... | |
const Camera * | CameraSensor () const |
Get a pointer to a camera sensor, or nullptr if the sensor does not contain a camera sensor. More... | |
void | ClearPlugins () |
Remove all plugins. More... | |
sdf::ElementPtr | Element () const |
Get a pointer to the SDF element that was used during load. More... | |
bool | EnableMetrics () const |
Get flag state for enabling performance metrics publication. More... | |
ForceTorque * | ForceTorqueSensor () |
Get a mutable force torque sensor, or nullptr if the sensor does not contain a force torque sensor. More... | |
const ForceTorque * | ForceTorqueSensor () const |
Get a pointer to a force torque sensor, or nullptr if the sensor does not contain a force torque sensor. More... | |
Imu * | ImuSensor () |
Get a mutable IMU sensor, or nullptr if the sensor does not contain an IMU sensor. More... | |
const Imu * | ImuSensor () const |
Get a pointer to an IMU sensor, or nullptr if the sensor does not contain an IMU sensor. More... | |
Lidar * | LidarSensor () |
Get a mutable lidar sensor, or nullptr if this sensor type is not a Lidar. More... | |
const Lidar * | LidarSensor () const |
Get the lidar sensor, or nullptr if this sensor type is not a Lidar. More... | |
Errors | Load (ElementPtr _sdf) |
Load the sensor based on a element pointer. More... | |
Magnetometer * | MagnetometerSensor () |
Get a mutable magnetometer sensor, or nullptr if this sensor type is not a Magnetometer. More... | |
const Magnetometer * | MagnetometerSensor () const |
Get the magnetometer sensor, or nullptr if this sensor type is not a Magnetometer. More... | |
std::string | Name () const |
Get the name of the sensor. More... | |
NavSat * | NavSatSensor () |
Get a mutable NAVSAT sensor, or nullptr if the sensor does not contain an NAVSAT sensor. More... | |
const NavSat * | NavSatSensor () const |
Get a pointer to a NAVSAT sensor, or nullptr if the sensor does not contain an NAVSAT sensor. More... | |
bool | operator!= (const Sensor &_sensor) const |
Return true this Sensor object does not contain the same values as the passed in parameter. More... | |
bool | operator== (const Sensor &_sensor) const |
Return true if both Sensor objects contain the same values. More... | |
sdf::Plugins & | Plugins () |
Get a mutable vector of plugins attached to this object. More... | |
const sdf::Plugins & | Plugins () const |
Get the plugins attached to this object. More... | |
const std::string & | PoseRelativeTo () const |
Get the name of the coordinate frame relative to which this object's pose is expressed. More... | |
const gz::math::Pose3d & | RawPose () const |
Get the pose of the sensor. More... | |
sdf::SemanticPose | SemanticPose () const |
Get SemanticPose object of this object to aid in resolving poses. More... | |
void | SetAirPressureSensor (const AirPressure &_air) |
Set the air pressure sensor. More... | |
void | SetAirSpeedSensor (const AirSpeed &_air) |
Set the air pressure sensor. More... | |
void | SetAltimeterSensor (const Altimeter &_alt) |
Set the altimeter sensor. More... | |
void | SetCameraSensor (const Camera &_cam) |
Set the camera sensor. More... | |
void | SetEnableMetrics (bool _enableMetrics) |
Set flag to enable publishing performance metrics. More... | |
void | SetForceTorqueSensor (const ForceTorque &_ft) |
Set the force torque sensor. More... | |
void | SetImuSensor (const Imu &_imu) |
Set the IMU sensor. More... | |
void | SetLidarSensor (const Lidar &_lidar) |
Set the lidar sensor. More... | |
void | SetMagnetometerSensor (const Magnetometer &_mag) |
Set the magnetometer sensor. More... | |
void | SetName (const std::string &_name) |
Set the name of the sensor. More... | |
void | SetNavSatSensor (const NavSat &_navsat) |
Set the NAVSAT sensor. More... | |
void | SetPoseRelativeTo (const std::string &_frame) |
Set the name of the coordinate frame relative to which this object's pose is expressed. More... | |
void | SetRawPose (const gz::math::Pose3d &_pose) |
Set the pose of the sensor. More... | |
void | SetTopic (const std::string &_topic) |
Set the topic on which sensor data should be published. More... | |
void | SetType (const SensorType _type) |
Set the sensor type. More... | |
bool | SetType (const std::string &_typeStr) |
Set the sensor type from a string. More... | |
void | SetUpdateRate (double _hz) |
Set the update rate. More... | |
sdf::ElementPtr | ToElement () const |
Create and return an SDF element filled with data from this sensor. More... | |
sdf::ElementPtr | ToElement (sdf::Errors &_errors) const |
Create and return an SDF element filled with data from this sensor. More... | |
std::string | Topic () const |
Get the topic on which sensor data should be published. More... | |
SensorType | Type () const |
Get the sensor type. More... | |
std::string | TypeStr () const |
Get the sensor type as a string. More... | |
double | UpdateRate () const |
Get the update rate in Hz. More... | |
Information about an SDF sensor.
sdf::SDF_VERSION_NAMESPACE::Sensor::Sensor | ( | ) |
Default constructor.
void sdf::SDF_VERSION_NAMESPACE::Sensor::AddPlugin | ( | const Plugin & | _plugin | ) |
Add a plugin to this object.
[in] | _plugin | Plugin to add. |
AirPressure* sdf::SDF_VERSION_NAMESPACE::Sensor::AirPressureSensor | ( | ) |
Get a mutable air pressure sensor, or nullptr if this sensor type is not an AirPressure sensor.
const AirPressure* sdf::SDF_VERSION_NAMESPACE::Sensor::AirPressureSensor | ( | ) | const |
Get the air pressure sensor, or nullptr if this sensor type is not an AirPressure sensor.
AirSpeed* sdf::SDF_VERSION_NAMESPACE::Sensor::AirSpeedSensor | ( | ) |
Get a mutable air speed sensor, or nullptr if this sensor type is not an AirSpeed sensor.
const AirSpeed* sdf::SDF_VERSION_NAMESPACE::Sensor::AirSpeedSensor | ( | ) | const |
Get the air speed sensor, or nullptr if this sensor type is not an AirSpeed sensor.
Altimeter* sdf::SDF_VERSION_NAMESPACE::Sensor::AltimeterSensor | ( | ) |
Get a mutable altimeter sensor, or nullptr if this sensor type is not an Altimeter.
const Altimeter* sdf::SDF_VERSION_NAMESPACE::Sensor::AltimeterSensor | ( | ) | const |
Get the altimeter sensor, or nullptr if this sensor type is not an Altimeter.
Camera* sdf::SDF_VERSION_NAMESPACE::Sensor::CameraSensor | ( | ) |
Get a mutable camera sensor, or nullptr if the sensor does not contain a camera sensor.
const Camera* sdf::SDF_VERSION_NAMESPACE::Sensor::CameraSensor | ( | ) | const |
Get a pointer to a camera sensor, or nullptr if the sensor does not contain a camera sensor.
void sdf::SDF_VERSION_NAMESPACE::Sensor::ClearPlugins | ( | ) |
Remove all plugins.
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Sensor::Element | ( | ) | const |
bool sdf::SDF_VERSION_NAMESPACE::Sensor::EnableMetrics | ( | ) | const |
Get flag state for enabling performance metrics publication.
ForceTorque* sdf::SDF_VERSION_NAMESPACE::Sensor::ForceTorqueSensor | ( | ) |
Get a mutable force torque sensor, or nullptr if the sensor does not contain a force torque sensor.
const ForceTorque* sdf::SDF_VERSION_NAMESPACE::Sensor::ForceTorqueSensor | ( | ) | const |
Get a pointer to a force torque sensor, or nullptr if the sensor does not contain a force torque sensor.
Imu* sdf::SDF_VERSION_NAMESPACE::Sensor::ImuSensor | ( | ) |
Get a mutable IMU sensor, or nullptr if the sensor does not contain an IMU sensor.
const Imu* sdf::SDF_VERSION_NAMESPACE::Sensor::ImuSensor | ( | ) | const |
Get a pointer to an IMU sensor, or nullptr if the sensor does not contain an IMU sensor.
Lidar* sdf::SDF_VERSION_NAMESPACE::Sensor::LidarSensor | ( | ) |
Get a mutable lidar sensor, or nullptr if this sensor type is not a Lidar.
const Lidar* sdf::SDF_VERSION_NAMESPACE::Sensor::LidarSensor | ( | ) | const |
Get the lidar sensor, or nullptr if this sensor type is not a Lidar.
Errors sdf::SDF_VERSION_NAMESPACE::Sensor::Load | ( | ElementPtr | _sdf | ) |
Magnetometer* sdf::SDF_VERSION_NAMESPACE::Sensor::MagnetometerSensor | ( | ) |
Get a mutable magnetometer sensor, or nullptr if this sensor type is not a Magnetometer.
const Magnetometer* sdf::SDF_VERSION_NAMESPACE::Sensor::MagnetometerSensor | ( | ) | const |
Get the magnetometer sensor, or nullptr if this sensor type is not a Magnetometer.
std::string sdf::SDF_VERSION_NAMESPACE::Sensor::Name | ( | ) | const |
Get the name of the sensor.
The name of the sensor should be unique within the scope of a World.
NavSat* sdf::SDF_VERSION_NAMESPACE::Sensor::NavSatSensor | ( | ) |
Get a mutable NAVSAT sensor, or nullptr if the sensor does not contain an NAVSAT sensor.
const NavSat* sdf::SDF_VERSION_NAMESPACE::Sensor::NavSatSensor | ( | ) | const |
Get a pointer to a NAVSAT sensor, or nullptr if the sensor does not contain an NAVSAT sensor.
bool sdf::SDF_VERSION_NAMESPACE::Sensor::operator!= | ( | const Sensor & | _sensor | ) | const |
bool sdf::SDF_VERSION_NAMESPACE::Sensor::operator== | ( | const Sensor & | _sensor | ) | const |
sdf::Plugins& sdf::SDF_VERSION_NAMESPACE::Sensor::Plugins | ( | ) |
Get a mutable vector of plugins attached to this object.
const sdf::Plugins& sdf::SDF_VERSION_NAMESPACE::Sensor::Plugins | ( | ) | const |
Get the plugins attached to this object.
const std::string& sdf::SDF_VERSION_NAMESPACE::Sensor::PoseRelativeTo | ( | ) | const |
Get the name of the coordinate frame relative to which this object's pose is expressed.
An empty value indicates that the frame is relative to the parent link/joint coordinate frame.
const gz::math::Pose3d& sdf::SDF_VERSION_NAMESPACE::Sensor::RawPose | ( | ) | const |
Get the pose of the sensor.
This is the pose of the sensor as specified in SDF (<sensor> <pose> ... </pose></sensor>), and is typically used to express the position and rotation of a sensor in a global coordinate frame.
sdf::SemanticPose sdf::SDF_VERSION_NAMESPACE::Sensor::SemanticPose | ( | ) | const |
Get SemanticPose object of this object to aid in resolving poses.
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetAirPressureSensor | ( | const AirPressure & | _air | ) |
Set the air pressure sensor.
[in] | _air | The air pressure sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetAirSpeedSensor | ( | const AirSpeed & | _air | ) |
Set the air pressure sensor.
[in] | _air | The air pressure sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetAltimeterSensor | ( | const Altimeter & | _alt | ) |
Set the altimeter sensor.
[in] | _alt | The altimeter sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetCameraSensor | ( | const Camera & | _cam | ) |
Set the camera sensor.
[in] | _cam | The camera sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetEnableMetrics | ( | bool | _enableMetrics | ) |
Set flag to enable publishing performance metrics.
[in] | _enableMetrics | True to enable. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetForceTorqueSensor | ( | const ForceTorque & | _ft | ) |
Set the force torque sensor.
[in] | _ft | The force torque sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetImuSensor | ( | const Imu & | _imu | ) |
Set the IMU sensor.
[in] | _imu | The IMU sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetLidarSensor | ( | const Lidar & | _lidar | ) |
Set the lidar sensor.
[in] | _lidar | The lidar sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetMagnetometerSensor | ( | const Magnetometer & | _mag | ) |
Set the magnetometer sensor.
[in] | _mag | The magnetometer sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetName | ( | const std::string & | _name | ) |
Set the name of the sensor.
The name of the sensor should be unique within the scope of a World.
[in] | _name | Name of the sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetNavSatSensor | ( | const NavSat & | _navsat | ) |
Set the NAVSAT sensor.
[in] | _navsat | The NAVSAT sensor. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetPoseRelativeTo | ( | const std::string & | _frame | ) |
Set the name of the coordinate frame relative to which this object's pose is expressed.
An empty value indicates that the frame is relative to the parent link/joint coordinate frame.
[in] | _frame | The name of the pose relative-to frame. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetRawPose | ( | const gz::math::Pose3d & | _pose | ) |
Set the pose of the sensor.
[in] | _pose | The new sensor pose. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetTopic | ( | const std::string & | _topic | ) |
Set the topic on which sensor data should be published.
[in] | _topic | Topic for this sensor's data. |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetType | ( | const SensorType | _type | ) |
Set the sensor type.
[in] | _type | The sensor type. |
bool sdf::SDF_VERSION_NAMESPACE::Sensor::SetType | ( | const std::string & | _typeStr | ) |
Set the sensor type from a string.
[in] | _typeStr | The sensor type. A valid parameter should equal one of the enum value name in the SensorType enum. For example, "altimeter" or "camera". |
void sdf::SDF_VERSION_NAMESPACE::Sensor::SetUpdateRate | ( | double | _hz | ) |
Set the update rate.
This is The frequency at which the sensor data is generated. If left unspecified (0.0), the sensor will generate data every cycle.
[in] | _rate | The update rate in Hz. |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Sensor::ToElement | ( | ) | const |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Sensor::ToElement | ( | sdf::Errors & | _errors | ) | const |
std::string sdf::SDF_VERSION_NAMESPACE::Sensor::Topic | ( | ) | const |
Get the topic on which sensor data should be published.
SensorType sdf::SDF_VERSION_NAMESPACE::Sensor::Type | ( | ) | const |
Get the sensor type.
std::string sdf::SDF_VERSION_NAMESPACE::Sensor::TypeStr | ( | ) | const |
Get the sensor type as a string.
double sdf::SDF_VERSION_NAMESPACE::Sensor::UpdateRate | ( | ) | const |
Get the update rate in Hz.
This is The frequency at which the sensor data is generated. If left unspecified (0.0), the sensor will generate data every cycle.