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

#include <GPSROSPlugin.hh>

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

Public Member Functions

 GPSROSPlugin ()
 Class constructor. More...
 
virtual void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load module and read parameters from SDF. More...
 
bool OnUpdateGPS ()
 Update GPS ROS message. More...
 
virtual ~GPSROSPlugin ()
 Class destructor. More...
 
- Public Member Functions inherited from gazebo::ROSBaseSensorPlugin
 ROSBaseSensorPlugin ()
 Class constructor. More...
 
virtual ~ROSBaseSensorPlugin ()
 Class destructor. More...
 
- Public Member Functions inherited from gazebo::ROSBasePlugin
bool AddNoiseModel (std::string _name, double _sigma)
 Add noise normal distribution to the list. More...
 
bool InitBasePlugin (sdf::ElementPtr _sdf)
 Initialize base plugin. More...
 
 ROSBasePlugin ()
 Class constructor. More...
 
virtual ~ROSBasePlugin ()
 Class destructor. More...
 

Protected Attributes

sensors::GpsSensorPtr gazeboGPSSensor
 Pointer to the parent sensor. More...
 
sensor_msgs::NavSatFix gpsMessage
 Output GPS ROS message. More...
 
- Protected Attributes inherited from gazebo::ROSBaseSensorPlugin
sensors::SensorPtr parentSensor
 Pointer to the parent sensor. More...
 
- Protected Attributes inherited from gazebo::ROSBasePlugin
ros::ServiceServer changeSensorSrv
 Service server object. More...
 
bool gazeboMsgEnabled
 Flag set to true if the Gazebo sensors messages are supposed to be published as well (it can avoid unnecessary overhead in case) the sensor messages needed are only ROS messages. More...
 
transport::NodePtr gazeboNode
 Gazebo's node handle for transporting measurement messages. More...
 
transport::PublisherPtr gazeboSensorOutputPub
 Gazebo's publisher for transporting measurement messages. More...
 
std_msgs::Bool isOn
 Flag to control the generation of output messages. More...
 
bool isReferenceInit
 Flag set to true if reference frame initialized. More...
 
common::Time lastMeasurementTime
 (Simulation) time when the last sensor measurement was generated. More...
 
double noiseAmp
 Noise amplitude. More...
 
std::map< std::string, std::normal_distribution< double > > noiseModels
 Normal distribution describing the noise models. More...
 
double noiseSigma
 Noise standard deviation. More...
 
ros::Publisher pluginStatePub
 ROS publisher for the switchable sensor data. More...
 
ignition::math::Pose3d referenceFrame
 Pose of the reference frame wrt world frame. More...
 
std::string referenceFrameID
 Frame ID of the reference frame. More...
 
physics::LinkPtr referenceLink
 Reference link. More...
 
std::default_random_engine rndGen
 Pseudo random number generator. More...
 
std::string robotNamespace
 Robot namespace. More...
 
boost::shared_ptr< ros::NodeHandlerosNode
 ROS node handle for communication with ROS. More...
 
ros::Publisher rosSensorOutputPub
 Gazebo's publisher for transporting measurement messages. More...
 
std::string sensorOutputTopic
 Name of the sensor's output topic. More...
 
ros::Subscriber tfStaticSub
 ROS subscriber for the TF static reference frame. More...
 
event::ConnectionPtr updateConnection
 Pointer to the update event connection. More...
 
double updateRate
 Sensor update rate. More...
 
physics::WorldPtr world
 Pointer to the world. More...
 

Additional Inherited Members

- Protected Member Functions inherited from gazebo::ROSBaseSensorPlugin
virtual bool OnUpdate (const common::UpdateInfo &)
 Update callback from simulation. More...
 
- Protected Member Functions inherited from gazebo::ROSBasePlugin
bool ChangeSensorState (uuv_sensor_ros_plugins_msgs::ChangeSensorState::Request &_req, uuv_sensor_ros_plugins_msgs::ChangeSensorState::Response &_res)
 Change sensor state (ON/OFF) More...
 
bool EnableMeasurement (const common::UpdateInfo &_info) const
 Enables generation of simulated measurement if the timeout since the last update has been reached. More...
 
double GetGaussianNoise (double _amp)
 Returns noise value for a function with zero mean from the default Gaussian noise model. More...
 
double GetGaussianNoise (std::string _name, double _amp)
 Returns noise value for a function with zero mean from a Gaussian noise model according to the model name. More...
 
void GetTFMessage (const tf::tfMessage::ConstPtr &_msg)
 Callback function for the static TF message. More...
 
bool IsOn ()
 Returns true if the plugin is activated. More...
 
void PublishState ()
 Publish the current state of the plugin. More...
 
void UpdateReferenceFramePose ()
 Updates the pose of the reference frame wrt the world frame. More...
 

Detailed Description

Definition at line 27 of file GPSROSPlugin.hh.

Constructor & Destructor Documentation

gazebo::GPSROSPlugin::GPSROSPlugin ( )

Class constructor.

Definition at line 21 of file GPSROSPlugin.cc.

gazebo::GPSROSPlugin::~GPSROSPlugin ( )
virtual

Class destructor.

Definition at line 25 of file GPSROSPlugin.cc.

Member Function Documentation

void gazebo::GPSROSPlugin::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Load module and read parameters from SDF.

Reimplemented from gazebo::ROSBaseSensorPlugin.

Definition at line 29 of file GPSROSPlugin.cc.

bool gazebo::GPSROSPlugin::OnUpdateGPS ( )

Update GPS ROS message.

Definition at line 68 of file GPSROSPlugin.cc.

Member Data Documentation

sensors::GpsSensorPtr gazebo::GPSROSPlugin::gazeboGPSSensor
protected

Pointer to the parent sensor.

Definition at line 43 of file GPSROSPlugin.hh.

sensor_msgs::NavSatFix gazebo::GPSROSPlugin::gpsMessage
protected

Output GPS ROS message.

Definition at line 46 of file GPSROSPlugin.hh.


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


uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:20