DVLROSPlugin
class gazebo::DVLROSPlugin
¶
class gazebo::DVLROSPlugin : public gazebo::ROSBaseModelPlugin
TODO: Modify computation of velocity using the beams.
Summary¶
Members | Descriptions |
---|---|
public DVLROSPlugin () |
Class constructor. |
public virtual ~DVLROSPlugin () |
Class destructor. |
public virtual void Load (physics::ModelPtr _model,sdf::ElementPtr _sdf) |
Load the plugin. |
protected bool beamTransformsInitialized |
|
protected double altitude |
Measured altitude in meters. |
protected uuv_sensor_ros_plugins_msgs::DVL dvlROSMsg |
ROS DVL message. |
protected std::vector< uuv_sensor_ros_plugins_msgs::DVLBeam > dvlBeamMsgs |
|
protected ros::Publisher twistPub |
ROS publisher for twist data. |
protected geometry_msgs::TwistWithCovarianceStamped twistROSMsg |
Store pose message since many attributes do not change (cov.). |
protected std::vector< std::string > beamsLinkNames |
List of beam links. |
protected std::vector< std::string > beamTopics |
List of beam topics. |
protected std::vector< ignition::math::Pose3d > beamPoses |
List of poses of each beam wrt to the DVL frame. |
protected boost::shared_ptr< message_filters::TimeSynchronizer< sensor_msgs::Range, sensor_msgs::Range, sensor_msgs::Range, sensor_msgs::Range > > syncBeamMessages |
|
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > beamSub0 |
|
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > beamSub1 |
|
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > beamSub2 |
|
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > > beamSub3 |
|
protected tf::TransformListener transformListener |
|
protected virtual bool OnUpdate (const common::UpdateInfo & _info) |
Update sensor measurement. |
protected 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. |
protected bool UpdateBeamTransforms () |
Updates the poses of each beam wrt the DVL frame. |
Members¶
public
DVLROSPlugin
()
¶
Class constructor.
public virtual
~DVLROSPlugin
()
¶
Class destructor.
public virtual void
Load
(physics::ModelPtr _model,sdf::ElementPtr _sdf)
¶
Load the plugin.
protected bool
beamTransformsInitialized
¶
protected double
altitude
¶
Measured altitude in meters.
protected uuv_sensor_ros_plugins_msgs::DVL
dvlROSMsg
¶
ROS DVL message.
protected std::vector< uuv_sensor_ros_plugins_msgs::DVLBeam >
dvlBeamMsgs
¶
protected ros::Publisher
twistPub
¶
ROS publisher for twist data.
protected geometry_msgs::TwistWithCovarianceStamped
twistROSMsg
¶
Store pose message since many attributes do not change (cov.).
protected std::vector< std::string >
beamsLinkNames
¶
List of beam links.
protected std::vector< std::string >
beamTopics
¶
List of beam topics.
protected std::vector< ignition::math::Pose3d >
beamPoses
¶
List of poses of each beam wrt to the DVL frame.
protected boost::shared_ptr< message_filters::TimeSynchronizer< sensor_msgs::Range, sensor_msgs::Range, sensor_msgs::Range, sensor_msgs::Range > >
syncBeamMessages
¶
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > >
beamSub0
¶
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > >
beamSub1
¶
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > >
beamSub2
¶
protected boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Range > >
beamSub3
¶
protected tf::TransformListener
transformListener
¶
protected virtual bool
OnUpdate
(const common::UpdateInfo & _info)
¶
Update sensor measurement.
protected 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.
protected bool
UpdateBeamTransforms
()
¶
Updates the poses of each beam wrt the DVL frame.