Gazebo Sensors

API Reference

7.3.0
NavSatSensor Class Reference

NavSat Sensor Class. More...

#include <NavSatSensor.hh>

Public Member Functions

 NavSatSensor ()
 Constructor. More...
 
virtual ~NavSatSensor ()
 Destructor. More...
 
double Altitude () const
 Get NavSat altitude above sea level. More...
 
virtual bool HasConnections () const override
 Check if there are any subscribers. More...
 
virtual bool Init () override
 Initialize values in the sensor. More...
 
const math::Angle & Latitude () const
 Get the latitude of the NavSat, wrapped between +/- 180 degrees. More...
 
virtual bool Load (const sdf::Sensor &_sdf) override
 Load the sensor based on data from an sdf::Sensor object. More...
 
virtual bool Load (sdf::ElementPtr _sdf) override
 Load the sensor with SDF parameters. More...
 
const math::Angle & Longitude () const
 Get the longitude of the NavSat, wrapped between +/- 180 degrees. More...
 
void SetAltitude (double _altitude)
 Set the altitude of the NavSat. More...
 
void SetLatitude (const math::Angle &_latitude)
 Set the latitude of the NavSat. More...
 
void SetLongitude (const math::Angle &_longitude)
 Set the longitude of the NavSat. More...
 
void SetPosition (const math::Angle &_latitude, const math::Angle &_longitude, double _altitude=0.0)
 Easy short hand for setting the position of the sensor. More...
 
void SetVelocity (const math::Vector3d &_vel)
 Set the velocity of the NavSat in ENU world frame. More...
 
virtual bool Update (const std::chrono::steady_clock::duration &_now) override
 Update the sensor and generate data. More...
 
const math::Vector3d & Velocity () const
 Get the velocity of the NavSat sensor in the ENU world frame. More...
 
- Public Member Functions inherited from Sensor
virtual ~Sensor ()
 destructor More...
 
void AddSequence (gz::msgs::Header *_msg, const std::string &_seqKey="default")
 Add a sequence number to a gz::msgs::Header. This function can be called by a sensor that wants to add a sequence number to a sensor message in order to have improved accountability for generated sensor data. More...
 
bool EnableMetrics () const
 Get flag state for enabling performance metrics publication. More...
 
std::string FrameId () const
 FrameId. More...
 
SensorId Id () const
 Get the sensor's ID. More...
 
bool IsActive () const
 Get whether the sensor is enabled or not. More...
 
std::string Name () const
 Get name. More...
 
std::chrono::steady_clock::duration NextDataUpdateTime () const
 Return the next time the sensor will generate data. More...
 
std::string Parent () const
 Get parent link of the sensor. More...
 
gz::math::Pose3d Pose () const
 Get the current pose. More...
 
void PublishMetrics (const std::chrono::duration< double > &_now)
 Publishes information about the performance of the sensor. This method is called by Update(). More...
 
sdf::ElementPtr SDF () const
 Get the SDF used to load this sensor. More...
 
void SetActive (bool _active)
 Enable or disable the sensor. Disabled sensors will not generate or publish data unless Update is called with the '_force' argument set to true. More...
 
void SetEnableMetrics (bool _enableMetrics)
 Set flag to enable publishing performance metrics. More...
 
void SetFrameId (const std::string &_frameId)
 Set Frame ID of the sensor. More...
 
void SetNextDataUpdateTime (const std::chrono::steady_clock::duration &_time)
 Manually set the next time the sensor will generate data Useful for accomodating jumps backwards in time as well as specifying updates for non-uniformly updating sensors. More...
 
virtual void SetParent (const std::string &_parent)
 Set the parent of the sensor. More...
 
void SetPose (const gz::math::Pose3d &_pose)
 Update the pose of the sensor. More...
 
bool SetTopic (const std::string &_topic)
 Set topic where sensor data is published. More...
 
void SetUpdateRate (const double _hz)
 Set the update rate of the sensor. An update rate of zero means that the sensor is updated every cycle. It's zero by default. \detail Negative rates become zero. More...
 
std::string Topic () const
 Get topic where sensor data is published. More...
 
bool Update (const std::chrono::steady_clock::duration &_now, const bool _force)
 Update the sensor. More...
 
double UpdateRate () const
 Get the update rate of the sensor. More...
 

Additional Inherited Members

- Protected Member Functions inherited from Sensor
 Sensor ()
 constructor More...
 

Detailed Description

NavSat Sensor Class.

A sensor that reports position and velocity readings over Gazebo Transport using spherical coordinates (latitude / longitude).

By default, it publishes gz::msgs::NavSat messages on the /.../navsat topic.

This sensor assumes the world is using the East-North-Up (ENU) frame.

Constructor & Destructor Documentation

◆ NavSatSensor()

Constructor.

◆ ~NavSatSensor()

virtual ~NavSatSensor ( )
virtual

Destructor.

Member Function Documentation

◆ Altitude()

double Altitude ( ) const

Get NavSat altitude above sea level.

Returns
Altitude in meters

◆ HasConnections()

virtual bool HasConnections ( ) const
overridevirtual

Check if there are any subscribers.

Returns
True if there are subscribers, false otherwise

Reimplemented from Sensor.

◆ Init()

virtual bool Init ( )
overridevirtual

Initialize values in the sensor.

Returns
True on success

Reimplemented from Sensor.

◆ Latitude()

const math::Angle& Latitude ( ) const

Get the latitude of the NavSat, wrapped between +/- 180 degrees.

Returns
Latitude angle.

◆ Load() [1/2]

virtual bool Load ( const sdf::Sensor &  _sdf)
overridevirtual

Load the sensor based on data from an sdf::Sensor object.

Parameters
[in]_sdfSDF Sensor parameters.
Returns
true if loading was successful

Reimplemented from Sensor.

◆ Load() [2/2]

virtual bool Load ( sdf::ElementPtr  _sdf)
overridevirtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters.
Returns
true if loading was successful

Reimplemented from Sensor.

◆ Longitude()

const math::Angle& Longitude ( ) const

Get the longitude of the NavSat, wrapped between +/- 180 degrees.

Returns
Longitude angle.

◆ SetAltitude()

void SetAltitude ( double  _altitude)

Set the altitude of the NavSat.

Parameters
[in]_altitudealtitude of NavSat in meters

◆ SetLatitude()

void SetLatitude ( const math::Angle &  _latitude)

Set the latitude of the NavSat.

Parameters
[in]_latitudeLatitude of NavSat

◆ SetLongitude()

void SetLongitude ( const math::Angle &  _longitude)

Set the longitude of the NavSat.

Parameters
[in]_longitudeLongitude of NavSat

◆ SetPosition()

void SetPosition ( const math::Angle &  _latitude,
const math::Angle &  _longitude,
double  _altitude = 0.0 
)

Easy short hand for setting the position of the sensor.

Parameters
[in]_latitudeLatitude angle.
[in]_longitudeLongitude angle.
[in]_altitudeAltitude in meters; defaults to zero.

◆ SetVelocity()

void SetVelocity ( const math::Vector3d &  _vel)

Set the velocity of the NavSat in ENU world frame.

Parameters
[in]_velNavSat in meters per second.

◆ Update()

virtual bool Update ( const std::chrono::steady_clock::duration &  _now)
overridevirtual

Update the sensor and generate data.

Parameters
[in]_nowThe current time
Returns
true if the update was successfull

Implements Sensor.

◆ Velocity()

const math::Vector3d& Velocity ( ) const

Get the velocity of the NavSat sensor in the ENU world frame.

Returns
Velocity in meters per second

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