SphericalCoordinatesROSInterfacePlugin.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 
17 
18 #ifndef __SC_ROS_INTERFACE_PLUGIN_HH__
19 #define __SC_ROS_INTERFACE_PLUGIN_HH__
20 
21 #include <boost/scoped_ptr.hpp>
22 #include <gazebo/gazebo.hh>
23 #include <gazebo/common/Plugin.hh>
24 #include <gazebo/common/SphericalCoordinates.hh>
25 #include <gazebo/physics/World.hh>
26 #include <ros/ros.h>
27 #include <uuv_world_ros_plugins_msgs/SetOriginSphericalCoord.h>
28 #include <uuv_world_ros_plugins_msgs/GetOriginSphericalCoord.h>
29 #include <uuv_world_ros_plugins_msgs/TransformToSphericalCoord.h>
30 #include <uuv_world_ros_plugins_msgs/TransformFromSphericalCoord.h>
31 #include <geometry_msgs/Vector3.h>
32 
33 #include <map>
34 #include <string>
35 
36 namespace gazebo
37 {
38 
39 class SphericalCoordinatesROSInterfacePlugin : public WorldPlugin
40 {
43 
46 
48  public: void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
49 
51  public: bool GetOriginSphericalCoord(
52  uuv_world_ros_plugins_msgs::GetOriginSphericalCoord::Request& _req,
53  uuv_world_ros_plugins_msgs::GetOriginSphericalCoord::Response& _res);
54 
56  public: bool SetOriginSphericalCoord(
57  uuv_world_ros_plugins_msgs::SetOriginSphericalCoord::Request& _req,
58  uuv_world_ros_plugins_msgs::SetOriginSphericalCoord::Response& _res);
59 
61  public: bool TransformToSphericalCoord(
62  uuv_world_ros_plugins_msgs::TransformToSphericalCoord::Request& _req,
63  uuv_world_ros_plugins_msgs::TransformToSphericalCoord::Response& _res);
64 
66  public: bool TransformFromSphericalCoord(
67  uuv_world_ros_plugins_msgs::TransformFromSphericalCoord::Request& _req,
68  uuv_world_ros_plugins_msgs::TransformFromSphericalCoord::Response& _res);
69 
71  protected: boost::scoped_ptr<ros::NodeHandle> rosNode;
72 
74  protected: event::ConnectionPtr rosPublishConnection;
75 
77  protected: physics::WorldPtr world;
78 
80  protected: std::map<std::string, ros::ServiceServer> worldServices;
81 };
82 
83 }
84 
85 #endif // __SC_ROS_INTERFACE_PLUGIN_HH__
void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
bool GetOriginSphericalCoord(uuv_world_ros_plugins_msgs::GetOriginSphericalCoord::Request &_req, uuv_world_ros_plugins_msgs::GetOriginSphericalCoord::Response &_res)
Service call that returns the origin in WGS84 standard.
std::map< std::string, ros::ServiceServer > worldServices
All underwater world services.
bool SetOriginSphericalCoord(uuv_world_ros_plugins_msgs::SetOriginSphericalCoord::Request &_req, uuv_world_ros_plugins_msgs::SetOriginSphericalCoord::Response &_res)
Service call that returns the origin in WGS84 standard.
bool TransformToSphericalCoord(uuv_world_ros_plugins_msgs::TransformToSphericalCoord::Request &_req, uuv_world_ros_plugins_msgs::TransformToSphericalCoord::Response &_res)
Service call to transform from Cartesian to spherical coordinates.
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node&#39;s handle.
bool TransformFromSphericalCoord(uuv_world_ros_plugins_msgs::TransformFromSphericalCoord::Request &_req, uuv_world_ros_plugins_msgs::TransformFromSphericalCoord::Response &_res)
Service call to transform from spherical to Cartesian coordinates.


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