#include <ROSBasePlugin.hh>
Public Member Functions | |
bool | AddNoiseModel (std::string _name, double _sigma) |
Add noise normal distribution to the list. More... | |
bool | InitBasePlugin (sdf::ElementPtr _sdf) |
Initialize base plugin. More... | |
virtual bool | OnUpdate (const common::UpdateInfo &)=0 |
Update callback from simulation. More... | |
ROSBasePlugin () | |
Class constructor. More... | |
virtual | ~ROSBasePlugin () |
Class destructor. More... | |
Protected Member Functions | |
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... | |
Protected Attributes | |
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::NodeHandle > | rosNode |
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... | |
Definition at line 39 of file ROSBasePlugin.hh.
gazebo::ROSBasePlugin::ROSBasePlugin | ( | ) |
Class constructor.
Definition at line 21 of file ROSBasePlugin.cc.
|
virtual |
Class destructor.
Definition at line 37 of file ROSBasePlugin.cc.
bool gazebo::ROSBasePlugin::AddNoiseModel | ( | std::string | _name, |
double | _sigma | ||
) |
Add noise normal distribution to the list.
Definition at line 214 of file ROSBasePlugin.cc.
|
protected |
Change sensor state (ON/OFF)
Definition at line 176 of file ROSBasePlugin.cc.
|
protected |
Enables generation of simulated measurement if the timeout since the last update has been reached.
Definition at line 231 of file ROSBasePlugin.cc.
|
protected |
Returns noise value for a function with zero mean from the default Gaussian noise model.
Definition at line 200 of file ROSBasePlugin.cc.
|
protected |
Returns noise value for a function with zero mean from a Gaussian noise model according to the model name.
Definition at line 206 of file ROSBasePlugin.cc.
|
protected |
Callback function for the static TF message.
Definition at line 147 of file ROSBasePlugin.cc.
bool gazebo::ROSBasePlugin::InitBasePlugin | ( | sdf::ElementPtr | _sdf | ) |
Initialize base plugin.
Definition at line 46 of file ROSBasePlugin.cc.
|
protected |
Returns true if the plugin is activated.
Definition at line 225 of file ROSBasePlugin.cc.
|
pure virtual |
Update callback from simulation.
Implemented in gazebo::IMUROSPlugin, gazebo::MagnetometerROSPlugin, gazebo::PoseGTROSPlugin, gazebo::DVLROSPlugin, gazebo::ROSBaseModelPlugin, gazebo::ROSBaseSensorPlugin, gazebo::CPCROSPlugin, gazebo::RPTROSPlugin, and gazebo::SubseaPressureROSPlugin.
|
protected |
Publish the current state of the plugin.
Definition at line 194 of file ROSBasePlugin.cc.
|
protected |
Updates the pose of the reference frame wrt the world frame.
Definition at line 240 of file ROSBasePlugin.cc.
|
protected |
Service server object.
Definition at line 108 of file ROSBasePlugin.hh.
|
protected |
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.
Definition at line 83 of file ROSBasePlugin.hh.
|
protected |
Gazebo's node handle for transporting measurement messages.
Definition at line 99 of file ROSBasePlugin.hh.
|
protected |
Gazebo's publisher for transporting measurement messages.
Definition at line 105 of file ROSBasePlugin.hh.
|
protected |
Flag to control the generation of output messages.
Definition at line 93 of file ROSBasePlugin.hh.
|
protected |
Flag set to true if reference frame initialized.
Definition at line 123 of file ROSBasePlugin.hh.
|
protected |
(Simulation) time when the last sensor measurement was generated.
Definition at line 69 of file ROSBasePlugin.hh.
|
protected |
Noise amplitude.
Definition at line 78 of file ROSBasePlugin.hh.
|
protected |
Normal distribution describing the noise models.
Definition at line 90 of file ROSBasePlugin.hh.
|
protected |
Noise standard deviation.
Definition at line 75 of file ROSBasePlugin.hh.
|
protected |
ROS publisher for the switchable sensor data.
Definition at line 111 of file ROSBasePlugin.hh.
|
protected |
Pose of the reference frame wrt world frame.
Definition at line 114 of file ROSBasePlugin.hh.
|
protected |
Frame ID of the reference frame.
Definition at line 120 of file ROSBasePlugin.hh.
|
protected |
Reference link.
Definition at line 126 of file ROSBasePlugin.hh.
|
protected |
Pseudo random number generator.
Definition at line 86 of file ROSBasePlugin.hh.
|
protected |
Robot namespace.
Definition at line 57 of file ROSBasePlugin.hh.
|
protected |
ROS node handle for communication with ROS.
Definition at line 96 of file ROSBasePlugin.hh.
|
protected |
Gazebo's publisher for transporting measurement messages.
Definition at line 102 of file ROSBasePlugin.hh.
|
protected |
Name of the sensor's output topic.
Definition at line 60 of file ROSBasePlugin.hh.
|
protected |
ROS subscriber for the TF static reference frame.
Definition at line 117 of file ROSBasePlugin.hh.
|
protected |
Pointer to the update event connection.
Definition at line 66 of file ROSBasePlugin.hh.
|
protected |
Sensor update rate.
Definition at line 72 of file ROSBasePlugin.hh.
|
protected |
Pointer to the world.
Definition at line 63 of file ROSBasePlugin.hh.