ROSBasePlugin
class gazebo::ROSBasePlugin
¶
Summary¶
Members | Descriptions |
---|---|
public ROSBasePlugin () |
Class constructor. |
public virtual ~ROSBasePlugin () |
Class destructor. |
public bool InitBasePlugin (sdf::ElementPtr _sdf) |
Initialize base plugin. |
public bool OnUpdate (const common::UpdateInfo &) |
Update callback from simulation. |
public bool AddNoiseModel (std::string _name,double _sigma) |
Add noise normal distribution to the list. |
protected std::string robotNamespace |
Robot namespace. |
protected std::string sensorOutputTopic |
Name of the sensor's output topic. |
protected physics::WorldPtr world |
Pointer to the world. |
protected event::ConnectionPtr updateConnection |
Pointer to the update event connection. |
protected common::Time lastMeasurementTime |
(Simulation) time when the last sensor measurement was generated. |
protected double updateRate |
Sensor update rate. |
protected double noiseSigma |
Noise standard deviation. |
protected double noiseAmp |
Noise amplitude. |
protected 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. |
protected std::default_random_engine rndGen |
Pseudo random number generator. |
protected std::map< std::string, std::normal_distribution< double > > noiseModels |
Normal distribution describing the noise models. |
protected std_msgs::Bool isOn |
Flag to control the generation of output messages. |
protected boost::shared_ptr< ros::NodeHandle > rosNode |
ROS node handle for communication with ROS. |
protected transport::NodePtr gazeboNode |
Gazebo's node handle for transporting measurement messages. |
protected ros::Publisher rosSensorOutputPub |
Gazebo's publisher for transporting measurement messages. |
protected transport::PublisherPtr gazeboSensorOutputPub |
Gazebo's publisher for transporting measurement messages. |
protected ros::ServiceServer changeSensorSrv |
Service server object. |
protected ros::Publisher pluginStatePub |
ROS publisher for the switchable sensor data. |
protected ignition::math::Pose3d referenceFrame |
Pose of the reference frame wrt world frame. |
protected ros::Subscriber tfStaticSub |
ROS subscriber for the TF static reference frame. |
protected std::string referenceFrameID |
Frame ID of the reference frame. |
protected bool isReferenceInit |
Flag set to true if reference frame initialized. |
protected physics::LinkPtr referenceLink |
Reference link. |
protected bool IsOn () |
Returns true if the plugin is activated. |
protected void PublishState () |
Publish the current state of the plugin. |
protected bool ChangeSensorState (uuv_sensor_ros_plugins_msgs::ChangeSensorState::Request & _req,uuv_sensor_ros_plugins_msgs::ChangeSensorState::Response & _res) |
Change sensor state (ON/OFF) |
protected void GetTFMessage (const tf::tfMessage::ConstPtr & _msg) |
Callback function for the static TF message. |
protected double GetGaussianNoise (double _amp) |
Returns noise value for a function with zero mean from the default Gaussian noise model. |
protected 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. |
protected bool EnableMeasurement (const common::UpdateInfo & _info) const |
Enables generation of simulated measurement if the timeout since the last update has been reached. |
protected void UpdateReferenceFramePose () |
Updates the pose of the reference frame wrt the world frame. |
Members¶
public
ROSBasePlugin
()
¶
Class constructor.
public virtual
~ROSBasePlugin
()
¶
Class destructor.
public bool
InitBasePlugin
(sdf::ElementPtr _sdf)
¶
Initialize base plugin.
public bool
OnUpdate
(const common::UpdateInfo &)
¶
Update callback from simulation.
public bool
AddNoiseModel
(std::string _name,double _sigma)
¶
Add noise normal distribution to the list.
protected std::string
robotNamespace
¶
Robot namespace.
protected std::string
sensorOutputTopic
¶
Name of the sensor's output topic.
protected physics::WorldPtr
world
¶
Pointer to the world.
protected event::ConnectionPtr
updateConnection
¶
Pointer to the update event connection.
protected common::Time
lastMeasurementTime
¶
(Simulation) time when the last sensor measurement was generated.
protected double
updateRate
¶
Sensor update rate.
protected double
noiseSigma
¶
Noise standard deviation.
protected double
noiseAmp
¶
Noise amplitude.
protected 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.
protected std::default_random_engine
rndGen
¶
Pseudo random number generator.
protected std::map< std::string, std::normal_distribution< double > >
noiseModels
¶
Normal distribution describing the noise models.
protected std_msgs::Bool
isOn
¶
Flag to control the generation of output messages.
protected boost::shared_ptr< ros::NodeHandle >
rosNode
¶
ROS node handle for communication with ROS.
protected transport::NodePtr
gazeboNode
¶
Gazebo's node handle for transporting measurement messages.
protected ros::Publisher
rosSensorOutputPub
¶
Gazebo's publisher for transporting measurement messages.
protected transport::PublisherPtr
gazeboSensorOutputPub
¶
Gazebo's publisher for transporting measurement messages.
protected ros::ServiceServer
changeSensorSrv
¶
Service server object.
protected ros::Publisher
pluginStatePub
¶
ROS publisher for the switchable sensor data.
protected ignition::math::Pose3d
referenceFrame
¶
Pose of the reference frame wrt world frame.
protected ros::Subscriber
tfStaticSub
¶
ROS subscriber for the TF static reference frame.
protected std::string
referenceFrameID
¶
Frame ID of the reference frame.
protected bool
isReferenceInit
¶
Flag set to true if reference frame initialized.
protected physics::LinkPtr
referenceLink
¶
Reference link.
protected bool
IsOn
()
¶
Returns true if the plugin is activated.
protected void
PublishState
()
¶
Publish the current state of the plugin.
protected bool
ChangeSensorState
(uuv_sensor_ros_plugins_msgs::ChangeSensorState::Request & _req,uuv_sensor_ros_plugins_msgs::ChangeSensorState::Response & _res)
¶
Change sensor state (ON/OFF)
protected void
GetTFMessage
(const tf::tfMessage::ConstPtr & _msg)
¶
Callback function for the static TF message.
protected double
GetGaussianNoise
(double _amp)
¶
Returns noise value for a function with zero mean from the default Gaussian noise model.
protected 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.
protected bool
EnableMeasurement
(const common::UpdateInfo & _info) const
¶
Enables generation of simulated measurement if the timeout since the last update has been reached.
protected void
UpdateReferenceFramePose
()
¶
Updates the pose of the reference frame wrt the world frame.