Public Member Functions | Protected Attributes | List of all members
gazebo::SphericalCoordinatesROSInterfacePlugin Class Reference

#include <SphericalCoordinatesROSInterfacePlugin.hh>

Inheritance diagram for gazebo::SphericalCoordinatesROSInterfacePlugin:
Inheritance graph
[legend]

Public Member Functions

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. More...
 
void Load (physics::WorldPtr _world, sdf::ElementPtr _sdf)
 Load module and read parameters from SDF. More...
 
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. More...
 
 SphericalCoordinatesROSInterfacePlugin ()
 Constructor. More...
 
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. More...
 
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. More...
 
virtual ~SphericalCoordinatesROSInterfacePlugin ()
 Destructor. More...
 

Protected Attributes

boost::scoped_ptr< ros::NodeHandlerosNode
 Pointer to this ROS node's handle. More...
 
event::ConnectionPtr rosPublishConnection
 Connection for callbacks on update world. More...
 
physics::WorldPtr world
 Pointer to world. More...
 
std::map< std::string, ros::ServiceServerworldServices
 All underwater world services. More...
 

Detailed Description

Definition at line 39 of file SphericalCoordinatesROSInterfacePlugin.hh.

Constructor & Destructor Documentation

gazebo::SphericalCoordinatesROSInterfacePlugin::SphericalCoordinatesROSInterfacePlugin ( )

Constructor.

Definition at line 24 of file SphericalCoordinatesROSInterfacePlugin.cc.

gazebo::SphericalCoordinatesROSInterfacePlugin::~SphericalCoordinatesROSInterfacePlugin ( )
virtual

Destructor.

Definition at line 28 of file SphericalCoordinatesROSInterfacePlugin.cc.

Member Function Documentation

bool gazebo::SphericalCoordinatesROSInterfacePlugin::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.

Definition at line 145 of file SphericalCoordinatesROSInterfacePlugin.cc.

void gazebo::SphericalCoordinatesROSInterfacePlugin::Load ( physics::WorldPtr  _world,
sdf::ElementPtr  _sdf 
)

Load module and read parameters from SDF.

Definition at line 39 of file SphericalCoordinatesROSInterfacePlugin.cc.

bool gazebo::SphericalCoordinatesROSInterfacePlugin::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.

Definition at line 168 of file SphericalCoordinatesROSInterfacePlugin.cc.

bool gazebo::SphericalCoordinatesROSInterfacePlugin::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.

Definition at line 125 of file SphericalCoordinatesROSInterfacePlugin.cc.

bool gazebo::SphericalCoordinatesROSInterfacePlugin::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.

Definition at line 104 of file SphericalCoordinatesROSInterfacePlugin.cc.

Member Data Documentation

boost::scoped_ptr<ros::NodeHandle> gazebo::SphericalCoordinatesROSInterfacePlugin::rosNode
protected

Pointer to this ROS node's handle.

Definition at line 71 of file SphericalCoordinatesROSInterfacePlugin.hh.

event::ConnectionPtr gazebo::SphericalCoordinatesROSInterfacePlugin::rosPublishConnection
protected

Connection for callbacks on update world.

Definition at line 74 of file SphericalCoordinatesROSInterfacePlugin.hh.

physics::WorldPtr gazebo::SphericalCoordinatesROSInterfacePlugin::world
protected

Pointer to world.

Definition at line 77 of file SphericalCoordinatesROSInterfacePlugin.hh.

std::map<std::string, ros::ServiceServer> gazebo::SphericalCoordinatesROSInterfacePlugin::worldServices
protected

All underwater world services.

Definition at line 80 of file SphericalCoordinatesROSInterfacePlugin.hh.


The documentation for this class was generated from the following files:


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