UnderwaterCurrentROSPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
19 
20 #ifndef __UNDERWATER_CURRENT_ROS_PLUGIN_HH__
21 #define __UNDERWATER_CURRENT_ROS_PLUGIN_HH__
22 
23 #include <map>
24 #include <string>
25 
26 // Gazebo plugin
28 
29 #include <boost/scoped_ptr.hpp>
30 #include <gazebo/common/Plugin.hh>
31 #include <gazebo/physics/World.hh>
32 #include <ros/ros.h>
33 #include <geometry_msgs/TwistStamped.h>
34 #include <uuv_world_ros_plugins_msgs/SetCurrentModel.h>
35 #include <uuv_world_ros_plugins_msgs/GetCurrentModel.h>
36 #include <uuv_world_ros_plugins_msgs/SetCurrentVelocity.h>
37 #include <uuv_world_ros_plugins_msgs/SetCurrentDirection.h>
38 #include <uuv_world_ros_plugins_msgs/SetOriginSphericalCoord.h>
39 #include <uuv_world_ros_plugins_msgs/GetOriginSphericalCoord.h>
40 
42 {
44  {
47 
49  public: virtual ~UnderwaterCurrentROSPlugin();
50 
52  public: void Load(gazebo::physics::WorldPtr _world,
53  sdf::ElementPtr _sdf);
54 
57  public: bool UpdateCurrentVelocityModel(
58  uuv_world_ros_plugins_msgs::SetCurrentModel::Request& _req,
59  uuv_world_ros_plugins_msgs::SetCurrentModel::Response& _res);
60 
63  public: bool UpdateCurrentHorzAngleModel(
64  uuv_world_ros_plugins_msgs::SetCurrentModel::Request& _req,
65  uuv_world_ros_plugins_msgs::SetCurrentModel::Response& _res);
66 
69  public: bool UpdateCurrentVertAngleModel(
70  uuv_world_ros_plugins_msgs::SetCurrentModel::Request& _req,
71  uuv_world_ros_plugins_msgs::SetCurrentModel::Response& _res);
72 
75  public: bool GetCurrentVelocityModel(
76  uuv_world_ros_plugins_msgs::GetCurrentModel::Request& _req,
77  uuv_world_ros_plugins_msgs::GetCurrentModel::Response& _res);
78 
81  public: bool GetCurrentHorzAngleModel(
82  uuv_world_ros_plugins_msgs::GetCurrentModel::Request& _req,
83  uuv_world_ros_plugins_msgs::GetCurrentModel::Response& _res);
84 
87  public: bool GetCurrentVertAngleModel(
88  uuv_world_ros_plugins_msgs::GetCurrentModel::Request& _req,
89  uuv_world_ros_plugins_msgs::GetCurrentModel::Response& _res);
90 
92  public: bool UpdateCurrentVelocity(
93  uuv_world_ros_plugins_msgs::SetCurrentVelocity::Request& _req,
94  uuv_world_ros_plugins_msgs::SetCurrentVelocity::Response& _res);
95 
97  public: bool UpdateHorzAngle(
98  uuv_world_ros_plugins_msgs::SetCurrentDirection::Request& _req,
99  uuv_world_ros_plugins_msgs::SetCurrentDirection::Response& _res);
100 
102  public: bool UpdateVertAngle(
103  uuv_world_ros_plugins_msgs::SetCurrentDirection::Request& _req,
104  uuv_world_ros_plugins_msgs::SetCurrentDirection::Response& _res);
105 
107  private: void OnUpdateCurrentVel();
108 
110  private: std::map<std::string, ros::ServiceServer> worldServices;
111 
113  private: boost::scoped_ptr<ros::NodeHandle> rosNode;
114 
116  private: gazebo::event::ConnectionPtr rosPublishConnection;
117 
120 
122  private: gazebo::common::Time rosPublishPeriod;
123 
125  private: gazebo::common::Time lastRosPublishTime;
126  };
127 }
128 
129 #endif // __UNDERWATER_CURRENT_ROS_PLUGIN_HH__
ros::Publisher flowVelocityPub
Publisher for the flow velocity in the world frame.
gazebo::common::Time rosPublishPeriod
Period after which we should publish a message via ROS.
bool UpdateCurrentVertAngleModel(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...
bool UpdateCurrentVelocity(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.
bool GetCurrentVelocityModel(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.
bool UpdateHorzAngle(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.
bool UpdateCurrentHorzAngleModel(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...
gazebo::common::Time lastRosPublishTime
Last time we published a message via ROS.
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node&#39;s handle.
bool UpdateVertAngle(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.
bool UpdateCurrentVelocityModel(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.
bool GetCurrentHorzAngleModel(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...
std::map< std::string, ros::ServiceServer > worldServices
All underwater world services.
void Load(gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
gazebo::event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
bool GetCurrentVertAngleModel(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.


uuv_world_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:41