UnderwaterCurrentROSPlugin
class uuv_simulator_ros::UnderwaterCurrentROSPlugin¶
class uuv_simulator_ros::UnderwaterCurrentROSPlugin : public UnderwaterCurrentPlugin
Summary¶
| Members | Descriptions |
|---|---|
publicUnderwaterCurrentROSPlugin() |
Class constructor. |
public virtual~UnderwaterCurrentROSPlugin() |
Class destructor. |
public voidLoad(gazebo::physics::WorldPtr _world,sdf::ElementPtr _sdf) |
Load module and read parameters from SDF. |
public boolUpdateCurrentVelocityModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentModel::Response & _res) |
Service call to update the parameters for the velocity Gauss-Markov process model. |
public boolUpdateCurrentHorzAngleModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentModel::Response & _res) |
Service call to update the parameters for the horizontal angle Gauss-Markov process model. |
public boolUpdateCurrentVertAngleModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentModel::Response & _res) |
Service call to update the parameters for the vertical angle Gauss-Markov process model. |
public boolGetCurrentVelocityModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::GetCurrentModel::Response & _res) |
Service call to read the parameters for the velocity Gauss-Markov process model. |
public boolGetCurrentHorzAngleModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::GetCurrentModel::Response & _res) |
Service call to read the parameters for the horizontal angle Gauss-Markov process model. |
public boolGetCurrentVertAngleModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::GetCurrentModel::Response & _res) |
Service call to read the parameters for the vertical angle Gauss-Markov process model. |
public boolUpdateCurrentVelocity(uuv_world_ros_plugins_msgs::SetCurrentVelocity::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentVelocity::Response & _res) |
Service call to update the mean value of the flow velocity. |
public boolUpdateHorzAngle(uuv_world_ros_plugins_msgs::SetCurrentDirection::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentDirection::Response & _res) |
Service call to update the mean value of the horizontal angle. |
public boolUpdateVertAngle(uuv_world_ros_plugins_msgs::SetCurrentDirection::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentDirection::Response & _res) |
Service call to update the mean value of the vertical angle. |
Members¶
publicUnderwaterCurrentROSPlugin()¶
Class constructor.
public virtual~UnderwaterCurrentROSPlugin()¶
Class destructor.
public voidLoad(gazebo::physics::WorldPtr _world,sdf::ElementPtr _sdf)¶
Load module and read parameters from SDF.
public boolUpdateCurrentVelocityModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentModel::Response & _res)¶
Service call to update the parameters for the velocity Gauss-Markov process model.
public boolUpdateCurrentHorzAngleModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentModel::Response & _res)¶
Service call to update the parameters for the horizontal angle Gauss-Markov process model.
public boolUpdateCurrentVertAngleModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentModel::Response & _res)¶
Service call to update the parameters for the vertical angle Gauss-Markov process model.
public boolGetCurrentVelocityModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::GetCurrentModel::Response & _res)¶
Service call to read the parameters for the velocity Gauss-Markov process model.
public boolGetCurrentHorzAngleModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::GetCurrentModel::Response & _res)¶
Service call to read the parameters for the horizontal angle Gauss-Markov process model.
public boolGetCurrentVertAngleModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request & _req,uuv_world_ros_plugins_msgs::GetCurrentModel::Response & _res)¶
Service call to read the parameters for the vertical angle Gauss-Markov process model.
public boolUpdateCurrentVelocity(uuv_world_ros_plugins_msgs::SetCurrentVelocity::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentVelocity::Response & _res)¶
Service call to update the mean value of the flow velocity.
public boolUpdateHorzAngle(uuv_world_ros_plugins_msgs::SetCurrentDirection::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentDirection::Response & _res)¶
Service call to update the mean value of the horizontal angle.
public boolUpdateVertAngle(uuv_world_ros_plugins_msgs::SetCurrentDirection::Request & _req,uuv_world_ros_plugins_msgs::SetCurrentDirection::Response & _res)¶
Service call to update the mean value of the vertical angle.