18 #ifndef __SC_ROS_INTERFACE_PLUGIN_HH__ 19 #define __SC_ROS_INTERFACE_PLUGIN_HH__ 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> 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> 48 public:
void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
52 uuv_world_ros_plugins_msgs::GetOriginSphericalCoord::Request& _req,
53 uuv_world_ros_plugins_msgs::GetOriginSphericalCoord::Response& _res);
57 uuv_world_ros_plugins_msgs::SetOriginSphericalCoord::Request& _req,
58 uuv_world_ros_plugins_msgs::SetOriginSphericalCoord::Response& _res);
62 uuv_world_ros_plugins_msgs::TransformToSphericalCoord::Request& _req,
63 uuv_world_ros_plugins_msgs::TransformToSphericalCoord::Response& _res);
67 uuv_world_ros_plugins_msgs::TransformFromSphericalCoord::Request& _req,
68 uuv_world_ros_plugins_msgs::TransformFromSphericalCoord::Response& _res);
71 protected: boost::scoped_ptr<ros::NodeHandle>
rosNode;
77 protected: physics::WorldPtr
world;
85 #endif // __SC_ROS_INTERFACE_PLUGIN_HH__ physics::WorldPtr world
Pointer to world.
void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
virtual ~SphericalCoordinatesROSInterfacePlugin()
Destructor.
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's handle.
SphericalCoordinatesROSInterfacePlugin()
Constructor.
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.