18 #include <gazebo/physics/Base.hh>    19 #include <gazebo/physics/Model.hh>    20 #include <gazebo/physics/World.hh>    21 #include <gazebo/physics/Link.hh>    42     gzerr << 
"Not loading plugin since ROS has not been "    43           << 
"properly initialized.  Try starting gazebo with ros plugin:\n"    44           << 
"  gazebo -s libgazebo_ros_api_plugin.so\n";
    52     UnderwaterObjectPlugin::Load(_parent, _sdf);
    54   catch(gazebo::common::Exception &_e)
    56     gzerr << 
"Error loading plugin."    57           << 
"Please ensure that your model is correct."    63     _parent->GetName() + 
"/current_velocity", 10,
    67   this->
services[
"set_use_global_current_velocity"] =
    68     this->
rosNode->advertiseService(
    69       _parent->GetName() + 
"/set_use_global_current_velocity",
    72   this->services[
"set_added_mass_scaling"] =
    73     this->
rosNode->advertiseService(
    74       _parent->GetName() + 
"/set_added_mass_scaling",
    77   this->services[
"get_added_mass_scaling"] =
    78     this->
rosNode->advertiseService(
    79       _parent->GetName() + 
"/get_added_mass_scaling",
    82   this->services[
"set_damping_scaling"] =
    83     this->
rosNode->advertiseService(
    84         _parent->GetName() + 
"/set_damping_scaling",
    87   this->services[
"get_damping_scaling"] =
    88     this->
rosNode->advertiseService(
    89         _parent->GetName() + 
"/get_damping_scaling",
    92   this->services[
"set_volume_scaling"] =
    93     this->
rosNode->advertiseService(
    94         _parent->GetName() + 
"/set_volume_scaling",
    97   this->services[
"get_volume_scaling"] =
    98     this->
rosNode->advertiseService(
    99         _parent->GetName() + 
"/get_volume_scaling",
   102   this->services[
"set_fluid_density"] =
   103     this->
rosNode->advertiseService(
   104         _parent->GetName() + 
"/set_fluid_density",
   107   this->services[
"get_fluid_density"] =
   108     this->
rosNode->advertiseService(
   109         _parent->GetName() + 
"/get_fluid_density",
   112   this->services[
"set_volume_offset"] =
   113     this->
rosNode->advertiseService(
   114       _parent->GetName() + 
"/set_volume_offset",
   117   this->services[
"get_volume_offset"] =
   118     this->
rosNode->advertiseService(
   119       _parent->GetName() + 
"/get_volume_offset",
   122   this->services[
"set_added_mass_offset"] =
   123     this->
rosNode->advertiseService(
   124       _parent->GetName() + 
"/set_added_mass_offset",
   127   this->services[
"get_added_mass_offset"] =
   128     this->
rosNode->advertiseService(
   129       _parent->GetName() + 
"/get_added_mass_offset",
   132   this->services[
"set_linear_damping_offset"] =
   133     this->
rosNode->advertiseService(
   134       _parent->GetName() + 
"/set_linear_damping_offset",
   137   this->services[
"get_linear_damping_offset"] =
   138     this->
rosNode->advertiseService(
   139       _parent->GetName() + 
"/get_linear_damping_offset",
   142   this->services[
"set_linear_forward_speed_damping_offset"] =
   143     this->
rosNode->advertiseService(
   144       _parent->GetName() + 
"/set_linear_forward_speed_damping_offset",
   147   this->services[
"get_linear_forward_speed_damping_offset"] =
   148     this->
rosNode->advertiseService(
   149       _parent->GetName() + 
"/get_linear_forward_speed_damping_offset",
   152   this->services[
"set_nonlinear_damping_offset"] =
   153     this->
rosNode->advertiseService(
   154       _parent->GetName() + 
"/set_nonlinear_damping_offset",
   157   this->services[
"get_nonlinear_damping_offset"] =
   158     this->
rosNode->advertiseService(
   159       _parent->GetName() + 
"/get_nonlinear_damping_offset",
   162   this->services[
"get_model_properties"] =
   163     this->
rosNode->advertiseService(
   164       _parent->GetName() + 
"/get_model_properties",
   168     this->
rosNode->advertise<visualization_msgs::Marker>
   169     (_parent->GetName() + 
"/current_velocity_marker", 0);
   171   this->
rosHydroPub[
"using_global_current_velocity"] =
   172     this->
rosNode->advertise<std_msgs::Bool>
   173     (_parent->GetName() + 
"/using_global_current_velocity", 0);
   175   this->rosHydroPub[
"is_submerged"] =
   176     this->
rosNode->advertise<std_msgs::Bool>
   177     (_parent->GetName() + 
"/is_submerged", 0);
   195   UnderwaterObjectPlugin::Init();
   205   UnderwaterObjectPlugin::Update(_info);
   215   UnderwaterObjectPlugin::InitDebug(_link, _hydro);
   218   for (std::map<std::string,
   219     gazebo::transport::PublisherPtr>::iterator it = this->
hydroPub.begin();
   223       this->
rosNode->advertise<geometry_msgs::WrenchStamped>(
   224         it->second->GetTopic(), 10);
   225       gzmsg << 
"ROS TOPIC: " << it->second->GetTopic() << std::endl;
   231   gazebo::physics::LinkPtr _link)
   234   UnderwaterObjectPlugin::PublishRestoringForce(_link);
   237   if (this->
models.count(_link))
   239     if (!this->
models[_link]->GetDebugFlag())
   242     ignition::math::Vector3d restoring = this->
models[_link]->GetStoredVector(
   245     geometry_msgs::WrenchStamped msg;
   247       ignition::math::Vector3d(0, 0, 0), msg);
   248     this->
rosHydroPub[_link->GetName() + 
"/restoring"].publish(msg);
   256     gzwarn << 
"Base link name string is empty" << std::endl;
   257   std_msgs::Bool isSubmerged;
   259   this->
rosHydroPub[
"is_submerged"].publish(isSubmerged);
   265   visualization_msgs::Marker marker;
   266   marker.header.frame_id = 
"world";
   268   marker.ns = this->
model->GetName() + 
"/current_velocity_marker";
   270   marker.type = visualization_msgs::Marker::ARROW;
   275     marker.action = visualization_msgs::Marker::ADD;
   276     ignition::math::Pose3d pose;
   277 #if GAZEBO_MAJOR_VERSION >= 8   278     pose = this->
model->WorldPose();
   280     pose = this->
model->GetWorldPose().Ign();
   283     double pitch = std::atan2(
   288     ignition::math::Quaterniond qt(0.0, -pitch, yaw);
   289     marker.pose.position.x = pose.Pos().X();
   290     marker.pose.position.y = pose.Pos().Y();
   291     marker.pose.position.z = pose.Pos().Z() + 1.5;
   292     marker.pose.orientation.x = qt.X();
   293     marker.pose.orientation.y = qt.Y();
   294     marker.pose.orientation.z = qt.Z();
   295     marker.pose.orientation.w = qt.W();
   297     marker.scale.y = 0.1;
   298     marker.scale.z = 0.1;
   299     marker.color.a = 1.0;
   300     marker.color.r = 0.0;
   301     marker.color.g = 0.0;
   302     marker.color.b = 1.0;
   306     marker.action = visualization_msgs::Marker::DELETE;
   309   this->
rosHydroPub[
"current_velocity_marker"].publish(marker);
   311   std_msgs::Bool useGlobalMsg;
   313   this->
rosHydroPub[
"using_global_current_velocity"].publish(useGlobalMsg);
   318   gazebo::physics::LinkPtr _link)
   321   UnderwaterObjectPlugin::PublishRestoringForce(_link);
   324   if (this->
models.count(_link))
   326     if (!this->
models[_link]->GetDebugFlag())
   328     geometry_msgs::WrenchStamped msg;
   329     ignition::math::Vector3d force, torque;
   336     this->
rosHydroPub[_link->GetName() + 
"/added_mass"].publish(msg);
   343     this->
rosHydroPub[_link->GetName() + 
"/damping"].publish(msg);
   350     this->
rosHydroPub[_link->GetName() + 
"/added_coriolis"].publish(msg);
   356   ignition::math::Vector3d _force, ignition::math::Vector3d _torque,
   357   geometry_msgs::WrenchStamped &_output)
   359   _output.wrench.force.x = _force.X();
   360   _output.wrench.force.y = _force.Y();
   361   _output.wrench.force.z = _force.Z();
   363   _output.wrench.torque.x = _torque.X();
   364   _output.wrench.torque.y = _torque.Y();
   365   _output.wrench.torque.z = _torque.Z();
   366 #if GAZEBO_MAJOR_VERSION >= 8   367   _output.header.stamp = 
ros::Time(this->
world->SimTime().Double());
   369   _output.header.stamp = 
ros::Time(this->
world->GetSimTime().Double());
   375   const geometry_msgs::Vector3::ConstPtr &_msg)
   387   uuv_gazebo_ros_plugins_msgs::SetUseGlobalCurrentVel::Request& _req,
   388   uuv_gazebo_ros_plugins_msgs::SetUseGlobalCurrentVel::Response& _res)
   390   if (_req.use_global == this->useGlobalCurrent)
   399       gzmsg << this->
model->GetName() <<
   400         "::Now using global current velocity" << std::endl;
   402       gzmsg << this->
model->GetName() <<
   403         "::Using the current velocity under the namespace " <<
   404         this->
model->GetName() << std::endl;
   412   uuv_gazebo_ros_plugins_msgs::GetModelProperties::Request& _req,
   413   uuv_gazebo_ros_plugins_msgs::GetModelProperties::Response& _res)
   415   for (std::map<gazebo::physics::LinkPtr,
   419     gazebo::physics::LinkPtr link = it->first;
   422     _res.link_names.push_back(link->GetName());
   424     uuv_gazebo_ros_plugins_msgs::UnderwaterObjectModel 
model;
   426     std::vector<double> mat;
   428     hydro->GetParam(
"volume", param);
   429     model.volume = param;
   431     hydro->GetParam(
"fluid_density", param);
   432     model.fluid_density = param;
   434     hydro->GetParam(
"bbox_height", param);
   435     model.bbox_height = param;
   437     hydro->GetParam(
"bbox_length", param);
   438     model.bbox_length = param;
   440     hydro->GetParam(
"bbox_width", param);
   441     model.bbox_width = param;
   443     hydro->GetParam(
"added_mass", mat);
   444     model.added_mass = mat;
   446     hydro->GetParam(
"linear_damping", mat);
   447     model.linear_damping = mat;
   449     hydro->GetParam(
"linear_damping_forward_speed", mat);
   450     model.linear_damping_forward_speed = mat;
   452     hydro->GetParam(
"quadratic_damping", mat);
   453     model.quadratic_damping = mat;
   455     model.neutrally_buoyant = hydro->IsNeutrallyBuoyant();
   457     hydro->GetParam(
"center_of_buoyancy", mat);
   458     model.cob.x = mat[0];
   459     model.cob.y = mat[1];
   460     model.cob.z = mat[2];
   461 #if GAZEBO_MAJOR_VERSION >= 8   462     model.inertia.m = link->GetInertial()->Mass();
   463     model.inertia.ixx = link->GetInertial()->IXX();
   464     model.inertia.ixy = link->GetInertial()->IXY();
   465     model.inertia.ixz = link->GetInertial()->IXZ();
   466     model.inertia.iyy = link->GetInertial()->IYY();
   467     model.inertia.iyz = link->GetInertial()->IYZ();
   468     model.inertia.izz = link->GetInertial()->IZZ();
   470     model.inertia.com.x = link->GetInertial()->CoG().X();
   471     model.inertia.com.y = link->GetInertial()->CoG().Y();
   472     model.inertia.com.z = link->GetInertial()->CoG().Z();
   474     model.inertia.m = link->GetInertial()->GetMass();
   475     model.inertia.ixx = link->GetInertial()->GetIXX();
   476     model.inertia.ixy = link->GetInertial()->GetIXY();
   477     model.inertia.ixz = link->GetInertial()->GetIXZ();
   478     model.inertia.iyy = link->GetInertial()->GetIYY();
   479     model.inertia.iyz = link->GetInertial()->GetIYZ();
   480     model.inertia.izz = link->GetInertial()->GetIZZ();
   482     model.inertia.com.x = link->GetInertial()->GetCoG().x;
   483     model.inertia.com.y = link->GetInertial()->GetCoG().y;
   484     model.inertia.com.z = link->GetInertial()->GetCoG().z;
   486     _res.models.push_back(model);
   493   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   494   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   499     _res.success = 
false;
   500     _res.message = 
"Scaling factor cannot be negative";
   504     for (std::map<gazebo::physics::LinkPtr,
   509       hydro->SetParam(
"scaling_added_mass", _req.data);
   512     _res.message = 
"All links set with new added-mass scaling factor";
   519   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   520   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   523   models.begin()->second->GetParam(
"scaling_added_mass", _res.data);
   529   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   530   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   535     _res.success = 
false;
   536     _res.message = 
"Scaling factor cannot be negative";
   540     for (std::map<gazebo::physics::LinkPtr,
   545       hydro->SetParam(
"scaling_damping", _req.data);
   548     _res.message = 
"All links set with new damping scaling factor";
   555   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   556   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   559   models.begin()->second->GetParam(
"scaling_damping", _res.data);
   565   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   566   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   571     _res.success = 
false;
   572     _res.message = 
"Scaling factor cannot be negative";
   576     for (std::map<gazebo::physics::LinkPtr,
   581       hydro->SetParam(
"scaling_volume", _req.data);
   584     _res.message = 
"All links set with new volume scaling factor";
   591   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   592   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   595   models.begin()->second->GetParam(
"scaling_volume", _res.data);
   601   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   602   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   607     _res.success = 
false;
   608     _res.message = 
"Scaling factor cannot be negative";
   612     for (std::map<gazebo::physics::LinkPtr,
   617       hydro->SetParam(
"fluid_density", _req.data);
   620     _res.message = 
"All links set with new fluid density";
   627   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   628   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   631   models.begin()->second->GetParam(
"fluid_density", _res.data);
   637   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   638   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   641   for (std::map<gazebo::physics::LinkPtr,
   646     hydro->SetParam(
"offset_volume", _req.data);
   649   _res.message = 
"All links set with new volume offset";
   656   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   657   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   660   models.begin()->second->GetParam(
"offset_volume", _res.data);
   666   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   667   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   670   for (std::map<gazebo::physics::LinkPtr,
   675     hydro->SetParam(
"offset_added_mass", _req.data);
   678   _res.message = 
"All links set with new added-mass identity offset";
   685   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   686   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   689   models.begin()->second->GetParam(
"offset_added_mass", _res.data);
   695   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   696   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   699   for (std::map<gazebo::physics::LinkPtr,
   704     hydro->SetParam(
"offset_linear_damping", _req.data);
   707   _res.message = 
"All links set with new linear damping identity offset";
   714   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   715   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   718   models.begin()->second->GetParam(
"offset_linear_damping", _res.data);
   724   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   725   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   728   for (std::map<gazebo::physics::LinkPtr,
   733     hydro->SetParam(
"offset_lin_forward_speed_damping", _req.data);
   736   _res.message = 
"All links set with new linear forward speed damping identity offset";
   743   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   744   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   747   models.begin()->second->GetParam(
"offset_lin_forward_speed_damping", _res.data);
   753   uuv_gazebo_ros_plugins_msgs::SetFloat::Request& _req,
   754   uuv_gazebo_ros_plugins_msgs::SetFloat::Response& _res)
   757   for (std::map<gazebo::physics::LinkPtr,
   762     hydro->SetParam(
"offset_nonlin_damping", _req.data);
   765   _res.message = 
"All links set with new nonlinear damping identity offset";
   772   uuv_gazebo_ros_plugins_msgs::GetFloat::Request& _req,
   773   uuv_gazebo_ros_plugins_msgs::GetFloat::Response& _res)
   776   models.begin()->second->GetParam(
"offset_nonlin_damping", _res.data);
 std::map< gazebo::physics::LinkPtr, HydrodynamicModelPtr > models
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
std::map< std::string, gazebo::transport::PublisherPtr > hydroPub
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. 
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. 
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. 
virtual void InitDebug(gazebo::physics::LinkPtr _link, gazebo::HydrodynamicModelPtr _hydro)
Sets the topics used for publishing the intermediate data during the simulation. 
virtual void Reset()
Reset Module. 
#define UUV_ADDED_CORIOLIS_FORCE
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node's handle. 
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. 
virtual void PublishHydrodynamicWrenches(gazebo::physics::LinkPtr _link)
Publish hydrodynamic wrenches. 
ROSCPP_DECL bool isInitialized()
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. 
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...
gazebo::physics::WorldPtr world
GZ_REGISTER_MODEL_PLUGIN(UmbilicalPlugin)
ignition::math::Vector3d flowVelocity
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...
std::map< std::string, ros::Publisher > rosHydroPub
Publisher for current actual thrust. 
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. 
virtual void PublishCurrentVelocityMarker()
Publishes the current velocity marker. 
std::map< std::string, ros::ServiceServer > services
Map of services. 
#define UUV_DAMPING_TORQUE
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. 
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. 
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. 
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) ...
virtual void PublishIsSubmerged()
Publishes the state of the vehicle (is submerged) 
#define UUV_ADDED_CORIOLIS_TORQUE
virtual void GenWrenchMsg(ignition::math::Vector3d _force, ignition::math::Vector3d _torque, geometry_msgs::WrenchStamped &_output)
Returns the wrench message for debugging topics. 
geometry_msgs::TransformStamped nedTransform
virtual ~UnderwaterObjectROSPlugin()
Destructor. 
UnderwaterObjectROSPlugin()
Constructor. 
#define UUV_ADDED_MASS_FORCE
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load module and read parameters from SDF. 
virtual void PublishRestoringForce(gazebo::physics::LinkPtr _link)
Publish restoring force. 
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. 
virtual void Init()
Initialize Module. 
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. 
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. 
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. 
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. 
ros::Subscriber subLocalCurVel
Subscriber to locally calculated current velocity. 
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. 
virtual void Update(const gazebo::common::UpdateInfo &_info)
Update the simulation state. 
#define UUV_ADDED_MASS_TORQUE
gazebo::physics::ModelPtr model
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. 
tf2_ros::TransformBroadcaster tfBroadcaster
#define UUV_DAMPING_FORCE
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. 
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)