Skip to content

UnderwaterObjectROSPlugin

class uuv_simulator_ros::UnderwaterObjectROSPlugin

class uuv_simulator_ros::UnderwaterObjectROSPlugin
  : public UnderwaterObjectPlugin
Summary
Members Descriptions
publicUnderwaterObjectROSPlugin() Constructor.
public virtual~UnderwaterObjectROSPlugin() Destructor.
public voidLoad(gazebo::physics::ModelPtr _parent,sdf::ElementPtr _sdf) Load module and read parameters from SDF.
public virtual voidInit() Initialize Module.
public virtual voidReset() Reset Module.
public virtual voidUpdate(const gazebo::common::UpdateInfo & _info) Update the simulation state.
public voidUpdateLocalCurrentVelocity(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 boolSetUseGlobalCurrentVel(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 boolGetModelProperties(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 boolSetScalingAddedMass(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 boolGetScalingAddedMass(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 boolSetScalingDamping(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 boolGetScalingDamping(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 boolSetScalingVolume(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 boolGetScalingVolume(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 boolSetFluidDensity(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 boolGetFluidDensity(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res) Get current value for the fluid density.
public boolSetOffsetVolume(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 boolGetOffsetVolume(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 boolSetOffsetAddedMass(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 boolGetOffsetAddedMass(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 boolSetOffsetLinearDamping(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 boolGetOffsetLinearDamping(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 boolSetOffsetLinearForwardSpeedDamping(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 boolGetOffsetLinearForwardSpeedDamping(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 boolSetOffsetNonLinearDamping(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 boolGetOffsetNonLinearDamping(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 voidPublishRestoringForce(gazebo::physics::LinkPtr _link) Publish restoring force.
protected virtual voidPublishHydrodynamicWrenches(gazebo::physics::LinkPtr _link) Publish hydrodynamic wrenches.
protected virtual voidGenWrenchMsg(ignition::math::Vector3d _force,ignition::math::Vector3d _torque,geometry_msgs::WrenchStamped & _output) Returns the wrench message for debugging topics.
protected virtual voidInitDebug(gazebo::physics::LinkPtr _link,gazebo::HydrodynamicModelPtr _hydro) Sets the topics used for publishing the intermediate data during the simulation.
protected virtual voidPublishCurrentVelocityMarker() Publishes the current velocity marker.
protected virtual voidPublishIsSubmerged() Publishes the state of the vehicle (is submerged)
Members
publicUnderwaterObjectROSPlugin()

Constructor.

public virtual~UnderwaterObjectROSPlugin()

Destructor.

public voidLoad(gazebo::physics::ModelPtr _parent,sdf::ElementPtr _sdf)

Load module and read parameters from SDF.

public virtual voidInit()

Initialize Module.

public virtual voidReset()

Reset Module.

public virtual voidUpdate(const gazebo::common::UpdateInfo & _info)

Update the simulation state.

Parameters
  • _info Information used in the update event.
public voidUpdateLocalCurrentVelocity(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 boolSetUseGlobalCurrentVel(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 boolGetModelProperties(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 boolSetScalingAddedMass(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 boolGetScalingAddedMass(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 boolSetScalingDamping(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 boolGetScalingDamping(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 boolSetScalingVolume(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 boolGetScalingVolume(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 boolSetFluidDensity(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 boolGetFluidDensity(uuv_gazebo_ros_plugins_msgs::GetFloat::Request & _req,uuv_gazebo_ros_plugins_msgs::GetFloat::Response & _res)

Get current value for the fluid density.

public boolSetOffsetVolume(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 boolGetOffsetVolume(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 boolSetOffsetAddedMass(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 boolGetOffsetAddedMass(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 boolSetOffsetLinearDamping(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 boolGetOffsetLinearDamping(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 boolSetOffsetLinearForwardSpeedDamping(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 boolGetOffsetLinearForwardSpeedDamping(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 boolSetOffsetNonLinearDamping(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 boolGetOffsetNonLinearDamping(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.

Publish restoring force.

Parameters
  • _link Pointer to the link where the force information will be extracted from

Publish hydrodynamic wrenches.

Parameters
  • _link Pointer to the link where the force information will be extracted from
protected virtual voidGenWrenchMsg(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 voidInitDebug(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 voidPublishCurrentVelocityMarker()

Publishes the current velocity marker.

protected virtual voidPublishIsSubmerged()

Publishes the state of the vehicle (is submerged)