TODO: Modify computation of velocity using the beams. More...
#include <DVLROSPlugin.hh>
Public Member Functions | |
DVLROSPlugin () | |
Class constructor. More... | |
virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
Load the plugin. More... | |
virtual | ~DVLROSPlugin () |
Class destructor. More... | |
Public Member Functions inherited from gazebo::ROSBaseModelPlugin | |
ROSBaseModelPlugin () | |
Class constructor. More... | |
virtual | ~ROSBaseModelPlugin () |
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 Member Functions | |
void | OnBeamCallback (const sensor_msgs::RangeConstPtr &_range0, const sensor_msgs::RangeConstPtr &_range1, const sensor_msgs::RangeConstPtr &_range2, const sensor_msgs::RangeConstPtr &_range3) |
Get beam Range message update. More... | |
virtual bool | OnUpdate (const common::UpdateInfo &_info) |
Update sensor measurement. More... | |
bool | UpdateBeamTransforms () |
Updates the poses of each beam wrt the DVL frame. More... | |
Protected Member Functions inherited from gazebo::ROSBaseModelPlugin | |
void | SendLocalNEDTransform () |
Returns true if the base_link_ned frame exists. 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... | |
Protected Attributes | |
double | altitude |
Measured altitude in meters. More... | |
std::vector< ignition::math::Pose3d > | beamPoses |
List of poses of each beam wrt to the DVL frame. More... | |
std::vector< std::string > | beamsLinkNames |
List of beam links. More... | |
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > | beamSub0 |
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > | beamSub1 |
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > | beamSub2 |
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > | beamSub3 |
std::vector< std::string > | beamTopics |
List of beam topics. More... | |
bool | beamTransformsInitialized |
std::vector< uuv_sensor_ros_plugins_msgs::DVLBeam > | dvlBeamMsgs |
uuv_sensor_ros_plugins_msgs::DVL | dvlROSMsg |
ROS DVL message. More... | |
boost::shared_ptr< message_filters::TimeSynchronizer< sensor_msgs::Range, sensor_msgs::Range, sensor_msgs::Range, sensor_msgs::Range > > | syncBeamMessages |
tf::TransformListener | transformListener |
ros::Publisher | twistPub |
ROS publisher for twist data. More... | |
geometry_msgs::TwistWithCovarianceStamped | twistROSMsg |
Store pose message since many attributes do not change (cov.). More... | |
Protected Attributes inherited from gazebo::ROSBaseModelPlugin | |
bool | enableLocalNEDFrame |
True if a the local NED frame needs to be broadcasted. More... | |
physics::LinkPtr | link |
Pointer to the link. More... | |
ignition::math::Pose3d | localNEDFrame |
Pose of the local NED frame wrt link frame. More... | |
physics::ModelPtr | model |
Pointer to the model. More... | |
tf::TransformBroadcaster * | tfBroadcaster |
TF broadcaster for the local NED frame. More... | |
tf::StampedTransform | tfLocalNEDFrame |
Local NED TF frame. 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::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... | |
TODO: Modify computation of velocity using the beams.
Definition at line 39 of file DVLROSPlugin.hh.
gazebo::DVLROSPlugin::DVLROSPlugin | ( | ) |
Class constructor.
Definition at line 21 of file DVLROSPlugin.cc.
|
virtual |
Class destructor.
Definition at line 27 of file DVLROSPlugin.cc.
|
virtual |
Load the plugin.
Reimplemented from gazebo::ROSBaseModelPlugin.
Definition at line 31 of file DVLROSPlugin.cc.
|
protected |
Get beam Range message update.
Definition at line 232 of file DVLROSPlugin.cc.
|
protectedvirtual |
Update sensor measurement.
Reimplemented from gazebo::ROSBaseModelPlugin.
Definition at line 147 of file DVLROSPlugin.cc.
|
protected |
Updates the poses of each beam wrt the DVL frame.
Definition at line 267 of file DVLROSPlugin.cc.
|
protected |
Measured altitude in meters.
Definition at line 65 of file DVLROSPlugin.hh.
|
protected |
List of poses of each beam wrt to the DVL frame.
Definition at line 85 of file DVLROSPlugin.hh.
|
protected |
List of beam links.
Definition at line 79 of file DVLROSPlugin.hh.
|
protected |
Definition at line 92 of file DVLROSPlugin.hh.
|
protected |
Definition at line 95 of file DVLROSPlugin.hh.
|
protected |
Definition at line 98 of file DVLROSPlugin.hh.
|
protected |
Definition at line 101 of file DVLROSPlugin.hh.
|
protected |
List of beam topics.
Definition at line 82 of file DVLROSPlugin.hh.
|
protected |
Definition at line 62 of file DVLROSPlugin.hh.
|
protected |
Definition at line 70 of file DVLROSPlugin.hh.
|
protected |
ROS DVL message.
Definition at line 68 of file DVLROSPlugin.hh.
|
protected |
Definition at line 89 of file DVLROSPlugin.hh.
|
protected |
Definition at line 103 of file DVLROSPlugin.hh.
|
protected |
ROS publisher for twist data.
Definition at line 73 of file DVLROSPlugin.hh.
|
protected |
Store pose message since many attributes do not change (cov.).
Definition at line 76 of file DVLROSPlugin.hh.