SphericalCoordinatesROSInterfacePlugin
class gazebo::SphericalCoordinatesROSInterfacePlugin
¶
class gazebo::SphericalCoordinatesROSInterfacePlugin : public WorldPlugin
Summary¶
Members | Descriptions |
---|---|
public SphericalCoordinatesROSInterfacePlugin () |
Constructor. |
public virtual ~SphericalCoordinatesROSInterfacePlugin () |
Destructor. |
public void Load (physics::WorldPtr _world,sdf::ElementPtr _sdf) |
Load module and read parameters from SDF. |
public 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. |
public 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. |
public 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. |
public 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. |
protected boost::scoped_ptr< ros::NodeHandle > rosNode |
Pointer to this ROS node's handle. |
protected event::ConnectionPtr rosPublishConnection |
Connection for callbacks on update world. |
protected physics::WorldPtr world |
Pointer to world. |
protected std::map< std::string, ros::ServiceServer > worldServices |
All underwater world services. |
Members¶
public
SphericalCoordinatesROSInterfacePlugin
()
¶
Constructor.
public virtual
~SphericalCoordinatesROSInterfacePlugin
()
¶
Destructor.
public void
Load
(physics::WorldPtr _world,sdf::ElementPtr _sdf)
¶
Load module and read parameters from SDF.
public 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.
public 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.
public 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.
public 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.
protected boost::scoped_ptr< ros::NodeHandle >
rosNode
¶
Pointer to this ROS node's handle.
protected event::ConnectionPtr
rosPublishConnection
¶
Connection for callbacks on update world.
protected physics::WorldPtr
world
¶
Pointer to world.
protected std::map< std::string, ros::ServiceServer >
worldServices
¶
All underwater world services.