UnderwaterObjectROSPlugin
class uuv_simulator_ros::UnderwaterObjectROSPlugin
¶
class uuv_simulator_ros::UnderwaterObjectROSPlugin : public UnderwaterObjectPlugin
Summary¶
Members | Descriptions |
---|---|
public UnderwaterObjectROSPlugin () |
Constructor. |
public virtual ~UnderwaterObjectROSPlugin () |
Destructor. |
public void Load (gazebo::physics::ModelPtr _parent,sdf::ElementPtr _sdf) |
Load module and read parameters from SDF. |
public virtual void Init () |
Initialize Module. |
public virtual void Reset () |
Reset Module. |
public virtual void Update (const gazebo::common::UpdateInfo & _info) |
Update the simulation state. |
public void UpdateLocalCurrentVelocity (const geometry_msgs::Vector3::ConstPtr & _msg) |
Update the local current velocity, this data will be used only if the useGlobalCurrent flag is set to false. |
public bool SetUseGlobalCurrentVel (uuv_gazebo_ros_plugins_msgs::SetUseGlobalCurrentVel::Request & _req,uuv_gazebo_ros_plugins_msgs::SetUseGlobalCurrentVel::Response & _res) |
Set flag to use the global current velocity topic input. |
public bool GetModelProperties (uuv_gazebo_ros_plugins_msgs::GetModelProperties::Request & _req,uuv_gazebo_ros_plugins_msgs::GetModelProperties::Response & _res) |
Return the model properties, along with parameters from the hydrodynamic and hydrostatic models. |
public bool SetScalingAddedMass (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set the scaling factor for the added-mass matrix. |
public bool GetScalingAddedMass (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return current scaling factor for the added-mass matrix. |
public bool SetScalingDamping (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set a scaling factor for the overall damping matrix. |
public bool GetScalingDamping (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return the scaling factor for the overall damping matrix. |
public bool SetScalingVolume (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set scaling factor for the model's volume used for buoyancy force computation. |
public bool GetScalingVolume (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Get scaling factor for the model's volume used for buoyancy force computation. |
public bool SetFluidDensity (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set new fluid density (this will alter the value for the buoyancy force) |
public bool GetFluidDensity (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Get current value for the fluid density. |
public bool SetOffsetVolume (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set offset factor for the model's volume (this will alter the value for the buoyancy force) |
public bool GetOffsetVolume (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return the offset factor for the model's volume. |
public bool SetOffsetAddedMass (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set the offset factor for the added-mass matrix. |
public bool GetOffsetAddedMass (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return the offset factor for the added-mass matrix. |
public bool SetOffsetLinearDamping (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set the offset factor for the linear damping matrix. |
public bool GetOffsetLinearDamping (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return the offset factor for the linear damping matrix. |
public bool SetOffsetLinearForwardSpeedDamping (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set the offset factor for the linear forward speed damping matrix. |
public bool GetOffsetLinearForwardSpeedDamping (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return the offset factor for the linear forward speed damping matrix. |
public bool SetOffsetNonLinearDamping (uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res) |
Set the offset factor for the nonlinear damping matrix. |
public bool GetOffsetNonLinearDamping (uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) |
Return the offset factor for the nonlinear damping matrix. |
protected virtual void PublishRestoringForce (gazebo::physics::LinkPtr _link) |
Publish restoring force. |
protected virtual void PublishHydrodynamicWrenches (gazebo::physics::LinkPtr _link) |
Publish hydrodynamic wrenches. |
protected virtual void GenWrenchMsg (ignition::math::Vector3d _force,ignition::math::Vector3d _torque,geometry_msgs::WrenchStamped & _output) |
Returns the wrench message for debugging topics. |
protected virtual void InitDebug (gazebo::physics::LinkPtr _link,gazebo::HydrodynamicModelPtr _hydro) |
Sets the topics used for publishing the intermediate data during the simulation. |
protected virtual void PublishCurrentVelocityMarker () |
Publishes the current velocity marker. |
protected virtual void PublishIsSubmerged () |
Publishes the state of the vehicle (is submerged) |
Members¶
public
UnderwaterObjectROSPlugin
()
¶
Constructor.
public virtual
~UnderwaterObjectROSPlugin
()
¶
Destructor.
public void
Load
(gazebo::physics::ModelPtr _parent,sdf::ElementPtr _sdf)
¶
Load module and read parameters from SDF.
public virtual void
Init
()
¶
Initialize Module.
public virtual void
Reset
()
¶
Reset Module.
public virtual void
Update
(const gazebo::common::UpdateInfo & _info)
¶
Update the simulation state.
Parameters¶
_info
Information used in the update event.
public void
UpdateLocalCurrentVelocity
(const geometry_msgs::Vector3::ConstPtr & _msg)
¶
Update the local current velocity, this data will be used only if the useGlobalCurrent flag is set to false.
public bool
SetUseGlobalCurrentVel
(uuv_gazebo_ros_plugins_msgs::SetUseGlobalCurrentVel::Request & _req,uuv_gazebo_ros_plugins_msgs::SetUseGlobalCurrentVel::Response & _res)
¶
Set flag to use the global current velocity topic input.
public bool
GetModelProperties
(uuv_gazebo_ros_plugins_msgs::GetModelProperties::Request & _req,uuv_gazebo_ros_plugins_msgs::GetModelProperties::Response & _res)
¶
Return the model properties, along with parameters from the hydrodynamic and hydrostatic models.
public bool
SetScalingAddedMass
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set the scaling factor for the added-mass matrix.
public bool
GetScalingAddedMass
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return current scaling factor for the added-mass matrix.
public bool
SetScalingDamping
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set a scaling factor for the overall damping matrix.
public bool
GetScalingDamping
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return the scaling factor for the overall damping matrix.
public bool
SetScalingVolume
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set scaling factor for the model's volume used for buoyancy force computation.
public bool
GetScalingVolume
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Get scaling factor for the model's volume used for buoyancy force computation.
public bool
SetFluidDensity
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set new fluid density (this will alter the value for the buoyancy force)
public bool
GetFluidDensity
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Get current value for the fluid density.
public bool
SetOffsetVolume
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set offset factor for the model's volume (this will alter the value for the buoyancy force)
public bool
GetOffsetVolume
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return the offset factor for the model's volume.
public bool
SetOffsetAddedMass
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set the offset factor for the added-mass matrix.
public bool
GetOffsetAddedMass
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return the offset factor for the added-mass matrix.
public bool
SetOffsetLinearDamping
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set the offset factor for the linear damping matrix.
public bool
GetOffsetLinearDamping
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return the offset factor for the linear damping matrix.
public bool
SetOffsetLinearForwardSpeedDamping
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set the offset factor for the linear forward speed damping matrix.
public bool
GetOffsetLinearForwardSpeedDamping
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return the offset factor for the linear forward speed damping matrix.
public bool
SetOffsetNonLinearDamping
(uuv_gazebo_ros_plugins_msgs::SetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::SetFloat::Response & _res)
¶
Set the offset factor for the nonlinear damping matrix.
public bool
GetOffsetNonLinearDamping
(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)
¶
Return the offset factor for the nonlinear damping matrix.
protected virtual void
PublishRestoringForce
(gazebo::physics::LinkPtr _link)
¶
Publish restoring force.
Parameters¶
_link
Pointer to the link where the force information will be extracted from
protected virtual void
PublishHydrodynamicWrenches
(gazebo::physics::LinkPtr _link)
¶
Publish hydrodynamic wrenches.
Parameters¶
_link
Pointer to the link where the force information will be extracted from
protected virtual void
GenWrenchMsg
(ignition::math::Vector3d _force,ignition::math::Vector3d _torque,geometry_msgs::WrenchStamped & _output)
¶
Returns the wrench message for debugging topics.
Parameters¶
-
_force
Force vector -
_torque
Torque vector -
_output
Stamped wrench message to be updated
protected virtual void
InitDebug
(gazebo::physics::LinkPtr _link,gazebo::HydrodynamicModelPtr _hydro)
¶
Sets the topics used for publishing the intermediate data during the simulation.
Parameters¶
-
_link
Pointer to the link -
_hydro
Pointer to the hydrodynamic model
protected virtual void
PublishCurrentVelocityMarker
()
¶
Publishes the current velocity marker.
protected virtual void
PublishIsSubmerged
()
¶
Publishes the state of the vehicle (is submerged)