Public Member Functions | Public Attributes | Protected Member Functions | Private Attributes | List of all members
gazebo::AcousticPinger Class Reference

Implements a simulated range and bearing pinger localisation system. More...

#include <acoustic_pinger_plugin.hh>

Inheritance diagram for gazebo::AcousticPinger:
Inheritance graph
[legend]

Public Member Functions

 AcousticPinger ()
 Constructor. More...
 
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 
void PingerPositionCallback (const geometry_msgs::Vector3ConstPtr &_pos)
 Callback function called when receiving a new pinger position via the pinger subscription callback. More...
 
virtual ~AcousticPinger ()
 Destructor. More...
 

Public Attributes

std::mutex mutex
 Mutex to protect the position vector. More...
 
ros::Subscriber setPositionSub
 Subscribes to the topic that set the pinger position. More...
 

Protected Member Functions

virtual void Update ()
 Callback used by gazebo to update the plugin. More...
 

Private Attributes

gazebo::sensors::NoisePtr bearingNoise = nullptr
 Gazebo noise object for bearing angle. More...
 
gazebo::sensors::NoisePtr elevationNoise = nullptr
 Gazebo noise object for elevation angle. More...
 
std::string frameId
 String holding the frame id of the sensor. More...
 
common::Time lastUpdateTime
 Variable used to track time of last update. This is used to produce data at the correct rate. More...
 
physics::ModelPtr model
 Pointer to model object. More...
 
ignition::math::Vector3d position
 Vector storing the position of the pinger. More...
 
ros::Publisher rangeBearingPub
 Publisher used to send sensor messages generated by the plugin. More...
 
gazebo::sensors::NoisePtr rangeNoise = nullptr
 rangeNoise - Gazebo noise object for range. More...
 
std::unique_ptr< ros::NodeHandlerosNodeHandle
 Nodehandle used to integrate with the ROS system. More...
 
event::ConnectionPtr updateConnection
 Pointer used to connect gazebo callback to plugins update function. More...
 
float updateRate
 Sensor update rate. More...
 

Detailed Description

Implements a simulated range and bearing pinger localisation system.

Implements a range and bearing pinger system. This assumes that the pinger localisation has a mechanism for estimating the range and bearing of the pinger. Pinger estimates are published using a custom message to the ROS system along with a standard header. This should allow the tf library to transform the sensor reading between frames.

Accepts the following SDF parameters: <robotNamespace> - Set the namespace of the robot. Used to setup the ROS nodehandle. <frameId> - Tf frame of the sensor message. Used as part of the sensor message publication. <topicName> - Name of the topic that the sensor message will be published on <setPositionTopicName> - Name of the topic that is used to set the position of the simulated pinger sensor. <position> - Position of the simulated pinger. Defaults to origin. <updateRate> - Rate of simulated sensor messages. <rangeNoise> - Noise model for the range to the simulated pinger. <bearingNoise> - Noise model for the bearing to the simulated pinger. <elevationNoise> - Noise model for the elevation to the simulated pinger.

Definition at line 56 of file acoustic_pinger_plugin.hh.

Constructor & Destructor Documentation

AcousticPinger::AcousticPinger ( )

Constructor.

Definition at line 57 of file acoustic_pinger_plugin.cc.

AcousticPinger::~AcousticPinger ( )
virtual

Destructor.

Definition at line 62 of file acoustic_pinger_plugin.cc.

Member Function Documentation

void AcousticPinger::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Definition at line 67 of file acoustic_pinger_plugin.cc.

void AcousticPinger::PingerPositionCallback ( const geometry_msgs::Vector3ConstPtr &  _pos)

Callback function called when receiving a new pinger position via the pinger subscription callback.

Parameters
[in]_posNew pinger position.

Definition at line 307 of file acoustic_pinger_plugin.cc.

void AcousticPinger::Update ( )
protectedvirtual

Callback used by gazebo to update the plugin.

Definition at line 232 of file acoustic_pinger_plugin.cc.

Member Data Documentation

gazebo::sensors::NoisePtr gazebo::AcousticPinger::bearingNoise = nullptr
private

Gazebo noise object for bearing angle.

Definition at line 115 of file acoustic_pinger_plugin.hh.

gazebo::sensors::NoisePtr gazebo::AcousticPinger::elevationNoise = nullptr
private

Gazebo noise object for elevation angle.

Definition at line 118 of file acoustic_pinger_plugin.hh.

std::string gazebo::AcousticPinger::frameId
private

String holding the frame id of the sensor.

Definition at line 98 of file acoustic_pinger_plugin.hh.

common::Time gazebo::AcousticPinger::lastUpdateTime
private

Variable used to track time of last update. This is used to produce data at the correct rate.

Definition at line 105 of file acoustic_pinger_plugin.hh.

physics::ModelPtr gazebo::AcousticPinger::model
private

Pointer to model object.

Definition at line 91 of file acoustic_pinger_plugin.hh.

std::mutex gazebo::AcousticPinger::mutex

Mutex to protect the position vector.

Definition at line 88 of file acoustic_pinger_plugin.hh.

ignition::math::Vector3d gazebo::AcousticPinger::position
private

Vector storing the position of the pinger.

Definition at line 94 of file acoustic_pinger_plugin.hh.

ros::Publisher gazebo::AcousticPinger::rangeBearingPub
private

Publisher used to send sensor messages generated by the plugin.

Definition at line 85 of file acoustic_pinger_plugin.hh.

gazebo::sensors::NoisePtr gazebo::AcousticPinger::rangeNoise = nullptr
private

rangeNoise - Gazebo noise object for range.

Definition at line 112 of file acoustic_pinger_plugin.hh.

std::unique_ptr<ros::NodeHandle> gazebo::AcousticPinger::rosNodeHandle
private

Nodehandle used to integrate with the ROS system.

Definition at line 79 of file acoustic_pinger_plugin.hh.

ros::Subscriber gazebo::AcousticPinger::setPositionSub

Subscribes to the topic that set the pinger position.

Definition at line 82 of file acoustic_pinger_plugin.hh.

event::ConnectionPtr gazebo::AcousticPinger::updateConnection
private

Pointer used to connect gazebo callback to plugins update function.

Definition at line 108 of file acoustic_pinger_plugin.hh.

float gazebo::AcousticPinger::updateRate
private

Sensor update rate.

Definition at line 101 of file acoustic_pinger_plugin.hh.


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


usv_gazebo_plugins
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:47