Skip to content

ROSBasePlugin

class gazebo::ROSBasePlugin

Summary
Members Descriptions
publicROSBasePlugin() Class constructor.
public virtual~ROSBasePlugin() Class destructor.
public boolInitBasePlugin(sdf::ElementPtr _sdf) Initialize base plugin.
public boolOnUpdate(const common::UpdateInfo &) Update callback from simulation.
public boolAddNoiseModel(std::string _name,double _sigma) Add noise normal distribution to the list.
protected std::stringrobotNamespace Robot namespace.
protected std::stringsensorOutputTopic Name of the sensor's output topic.
protected physics::WorldPtrworld Pointer to the world.
protected event::ConnectionPtrupdateConnection Pointer to the update event connection.
protected common::TimelastMeasurementTime (Simulation) time when the last sensor measurement was generated.
protected doubleupdateRate Sensor update rate.
protected doublenoiseSigma Noise standard deviation.
protected doublenoiseAmp Noise amplitude.
protected boolgazeboMsgEnabled 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.
protected std::default_random_enginerndGen Pseudo random number generator.
protected std::map< std::string, std::normal_distribution< double > >noiseModels Normal distribution describing the noise models.
protected std_msgs::BoolisOn Flag to control the generation of output messages.
protected boost::shared_ptr< ros::NodeHandle >rosNode ROS node handle for communication with ROS.
protected transport::NodePtrgazeboNode Gazebo's node handle for transporting measurement messages.
protected ros::PublisherrosSensorOutputPub Gazebo's publisher for transporting measurement messages.
protected transport::PublisherPtrgazeboSensorOutputPub Gazebo's publisher for transporting measurement messages.
protected ros::ServiceServerchangeSensorSrv Service server object.
protected ros::PublisherpluginStatePub ROS publisher for the switchable sensor data.
protected ignition::math::Pose3dreferenceFrame Pose of the reference frame wrt world frame.
protected ros::SubscribertfStaticSub ROS subscriber for the TF static reference frame.
protected std::stringreferenceFrameID Frame ID of the reference frame.
protected boolisReferenceInit Flag set to true if reference frame initialized.
protected physics::LinkPtrreferenceLink Reference link.
protected boolIsOn() Returns true if the plugin is activated.
protected voidPublishState() Publish the current state of the plugin.
protected boolChangeSensorState(uuv_sensor_ros_plugins_msgs::ChangeSensorState::Request & _req,uuv_sensor_ros_plugins_msgs::ChangeSensorState::Response & _res) Change sensor state (ON/OFF)
protected voidGetTFMessage(const tf::tfMessage::ConstPtr & _msg) Callback function for the static TF message.
protected doubleGetGaussianNoise(double _amp) Returns noise value for a function with zero mean from the default Gaussian noise model.
protected doubleGetGaussianNoise(std::string _name,double _amp) Returns noise value for a function with zero mean from a Gaussian noise model according to the model name.
protected boolEnableMeasurement(const common::UpdateInfo & _info) const Enables generation of simulated measurement if the timeout since the last update has been reached.
protected voidUpdateReferenceFramePose() Updates the pose of the reference frame wrt the world frame.
Members
publicROSBasePlugin()

Class constructor.

public virtual~ROSBasePlugin()

Class destructor.

public boolInitBasePlugin(sdf::ElementPtr _sdf)

Initialize base plugin.

public boolOnUpdate(const common::UpdateInfo &)

Update callback from simulation.

public boolAddNoiseModel(std::string _name,double _sigma)

Add noise normal distribution to the list.

protected std::stringrobotNamespace

Robot namespace.

protected std::stringsensorOutputTopic

Name of the sensor's output topic.

protected physics::WorldPtrworld

Pointer to the world.

protected event::ConnectionPtrupdateConnection

Pointer to the update event connection.

protected common::TimelastMeasurementTime

(Simulation) time when the last sensor measurement was generated.

protected doubleupdateRate

Sensor update rate.

protected doublenoiseSigma

Noise standard deviation.

protected doublenoiseAmp

Noise amplitude.

protected boolgazeboMsgEnabled

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.

protected std::default_random_enginerndGen

Pseudo random number generator.

protected std::map< std::string, std::normal_distribution< double > >noiseModels

Normal distribution describing the noise models.

protected std_msgs::BoolisOn

Flag to control the generation of output messages.

protected boost::shared_ptr< ros::NodeHandle >rosNode

ROS node handle for communication with ROS.

protected transport::NodePtrgazeboNode

Gazebo's node handle for transporting measurement messages.

protected ros::PublisherrosSensorOutputPub

Gazebo's publisher for transporting measurement messages.

protected transport::PublisherPtrgazeboSensorOutputPub

Gazebo's publisher for transporting measurement messages.

protected ros::ServiceServerchangeSensorSrv

Service server object.

protected ros::PublisherpluginStatePub

ROS publisher for the switchable sensor data.

protected ignition::math::Pose3dreferenceFrame

Pose of the reference frame wrt world frame.

protected ros::SubscribertfStaticSub

ROS subscriber for the TF static reference frame.

protected std::stringreferenceFrameID

Frame ID of the reference frame.

protected boolisReferenceInit

Flag set to true if reference frame initialized.

Reference link.

protected boolIsOn()

Returns true if the plugin is activated.

protected voidPublishState()

Publish the current state of the plugin.

protected boolChangeSensorState(uuv_sensor_ros_plugins_msgs::ChangeSensorState::Request & _req,uuv_sensor_ros_plugins_msgs::ChangeSensorState::Response & _res)

Change sensor state (ON/OFF)

protected voidGetTFMessage(const tf::tfMessage::ConstPtr & _msg)

Callback function for the static TF message.

protected doubleGetGaussianNoise(double _amp)

Returns noise value for a function with zero mean from the default Gaussian noise model.

protected doubleGetGaussianNoise(std::string _name,double _amp)

Returns noise value for a function with zero mean from a Gaussian noise model according to the model name.

protected boolEnableMeasurement(const common::UpdateInfo & _info) const

Enables generation of simulated measurement if the timeout since the last update has been reached.

protected voidUpdateReferenceFramePose()

Updates the pose of the reference frame wrt the world frame.