#include <UnderwaterObjectROSPlugin.hh>
Public Member Functions | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
virtual void | Init () |
Initialize Module. More... | |
void | Load (gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load module and read parameters from SDF. More... | |
virtual void | Reset () |
Reset Module. More... | |
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) More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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) More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
UnderwaterObjectROSPlugin () | |
Constructor. More... | |
virtual void | Update (const gazebo::common::UpdateInfo &_info) |
Update the simulation state. More... | |
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. More... | |
virtual | ~UnderwaterObjectROSPlugin () |
Destructor. More... | |
Public Member Functions inherited from gazebo::UnderwaterObjectPlugin | |
UnderwaterObjectPlugin () | |
virtual | ~UnderwaterObjectPlugin () |
Protected Member Functions | |
virtual void | GenWrenchMsg (ignition::math::Vector3d _force, ignition::math::Vector3d _torque, geometry_msgs::WrenchStamped &_output) |
Returns the wrench message for debugging topics. More... | |
virtual void | InitDebug (gazebo::physics::LinkPtr _link, gazebo::HydrodynamicModelPtr _hydro) |
Sets the topics used for publishing the intermediate data during the simulation. More... | |
virtual void | PublishCurrentVelocityMarker () |
Publishes the current velocity marker. More... | |
virtual void | PublishHydrodynamicWrenches (gazebo::physics::LinkPtr _link) |
Publish hydrodynamic wrenches. More... | |
virtual void | PublishIsSubmerged () |
Publishes the state of the vehicle (is submerged) More... | |
virtual void | PublishRestoringForce (gazebo::physics::LinkPtr _link) |
Publish restoring force. More... | |
Protected Member Functions inherited from gazebo::UnderwaterObjectPlugin | |
virtual void | Connect () |
virtual void | GenWrenchMsg (ignition::math::Vector3d _force, ignition::math::Vector3d _torque, gazebo::msgs::WrenchStamped &_output) |
void | UpdateFlowVelocity (ConstVector3dPtr &_msg) |
Private Attributes | |
geometry_msgs::TransformStamped | nedTransform |
std::map< std::string, ros::Publisher > | rosHydroPub |
Publisher for current actual thrust. More... | |
boost::scoped_ptr< ros::NodeHandle > | rosNode |
Pointer to this ROS node's handle. More... | |
std::map< std::string, ros::ServiceServer > | services |
Map of services. More... | |
ros::Subscriber | subLocalCurVel |
Subscriber to locally calculated current velocity. More... | |
tf2_ros::TransformBroadcaster | tfBroadcaster |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::UnderwaterObjectPlugin | |
std::string | baseLinkName |
gazebo::transport::SubscriberPtr | flowSubscriber |
ignition::math::Vector3d | flowVelocity |
std::map< std::string, gazebo::transport::PublisherPtr > | hydroPub |
gazebo::physics::ModelPtr | model |
std::map< gazebo::physics::LinkPtr, HydrodynamicModelPtr > | models |
gazebo::transport::NodePtr | node |
gazebo::event::ConnectionPtr | updateConnection |
bool | useGlobalCurrent |
gazebo::physics::WorldPtr | world |
Definition at line 47 of file UnderwaterObjectROSPlugin.hh.
uuv_simulator_ros::UnderwaterObjectROSPlugin::UnderwaterObjectROSPlugin | ( | ) |
Constructor.
Definition at line 26 of file UnderwaterObjectROSPlugin.cc.
|
virtual |
Destructor.
Definition at line 31 of file UnderwaterObjectROSPlugin.cc.
|
protectedvirtual |
Returns the wrench message for debugging topics.
[in] | _force | Force vector |
[in] | _torque | Torque vector |
[in] | _output | Stamped wrench message to be updated |
Definition at line 355 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::GetFluidDensity | ( | uuv_gazebo_ros_plugins_msgs::GetFloat::Request & | _req, |
uuv_gazebo_ros_plugins_msgs::GetFloat::Response & | _res | ||
) |
Get current value for the fluid density.
Definition at line 626 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 411 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 684 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 713 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 742 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 771 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 655 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 518 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 554 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 590 of file UnderwaterObjectROSPlugin.cc.
|
virtual |
Initialize Module.
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 193 of file UnderwaterObjectROSPlugin.cc.
|
protectedvirtual |
Sets the topics used for publishing the intermediate data during the simulation.
[in] | _link | Pointer to the link |
[in] | _hydro | Pointer to the hydrodynamic model |
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 212 of file UnderwaterObjectROSPlugin.cc.
|
virtual |
Load module and read parameters from SDF.
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 37 of file UnderwaterObjectROSPlugin.cc.
|
protectedvirtual |
Publishes the current velocity marker.
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 263 of file UnderwaterObjectROSPlugin.cc.
|
protectedvirtual |
Publish hydrodynamic wrenches.
[in] | _link | Pointer to the link where the force information will be extracted from |
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 317 of file UnderwaterObjectROSPlugin.cc.
|
protectedvirtual |
Publishes the state of the vehicle (is submerged)
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 253 of file UnderwaterObjectROSPlugin.cc.
|
protectedvirtual |
Publish restoring force.
[in] | _link | Pointer to the link where the force information will be extracted from |
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 230 of file UnderwaterObjectROSPlugin.cc.
|
virtual |
Reset Module.
Definition at line 199 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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)
Definition at line 600 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 665 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 694 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 723 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 752 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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)
Definition at line 636 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 492 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 528 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 564 of file UnderwaterObjectROSPlugin.cc.
bool uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 386 of file UnderwaterObjectROSPlugin.cc.
|
virtual |
Update the simulation state.
[in] | _info | Information used in the update event. |
Reimplemented from gazebo::UnderwaterObjectPlugin.
Definition at line 203 of file UnderwaterObjectROSPlugin.cc.
void uuv_simulator_ros::UnderwaterObjectROSPlugin::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.
Definition at line 374 of file UnderwaterObjectROSPlugin.cc.
|
private |
Definition at line 227 of file UnderwaterObjectROSPlugin.hh.
|
private |
Publisher for current actual thrust.
Definition at line 222 of file UnderwaterObjectROSPlugin.hh.
|
private |
Pointer to this ROS node's handle.
Definition at line 216 of file UnderwaterObjectROSPlugin.hh.
|
private |
Map of services.
Definition at line 225 of file UnderwaterObjectROSPlugin.hh.
|
private |
Subscriber to locally calculated current velocity.
Definition at line 219 of file UnderwaterObjectROSPlugin.hh.
|
private |
Definition at line 229 of file UnderwaterObjectROSPlugin.hh.