Public Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRos Class Reference

#include <gazebo_ros_utils.h>

Public Member Functions

 GazeboRos (physics::ModelPtr &_parent, sdf::ElementPtr _sdf, const std::string &_plugin)
 
 GazeboRos (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_plugin)
 
physics::JointPtr getJoint (physics::ModelPtr &_parent, const char *_tag_name, const std::string &_joint_default_name)
 
template<class T >
void getParameter (T &_value, const char *_tag_name, const T &_default)
 
template<class T >
void getParameter (T &_value, const char *_tag_name)
 
template<class T >
void getParameter (T &_value, const char *_tag_name, const std::map< std::string, T > &_options, const T &_default)
 
template<class T >
void getParameter (T &_value, const char *_tag_name, const std::map< std::string, T > &_options)
 
void getParameterBoolean (bool &_value, const char *_tag_name, const bool &_default)
 
void getParameterBoolean (bool &_value, const char *_tag_name)
 
const char * info () const
 
void isInitialized ()
 
boost::shared_ptr< ros::NodeHandle > & node ()
 
const boost::shared_ptr< ros::NodeHandle > & node () const
 
std::string resolveTF (const std::string &_name)
 

Private Member Functions

void readCommonParameter ()
 info text for log messages to identify the node More...
 

Private Attributes

std::string info_text
 prefix for the ros tf plublisher if not set it uses the namespace_ More...
 
std::string namespace_
 name of the plugin class More...
 
std::string plugin_
 sdf to read More...
 
boost::shared_ptr< ros::NodeHandlerosnode_
 name of the launched node More...
 
sdf::ElementPtr sdf_
 
std::string tf_prefix_
 rosnode More...
 

Detailed Description

Gazebo ros helper class The class simplifies the parameter and rosnode handling

Author
Markus Bader marku.nosp@m.s.ba.nosp@m.der@t.nosp@m.uwie.nosp@m.n.ac..nosp@m.at

Definition at line 109 of file gazebo_ros_utils.h.

Constructor & Destructor Documentation

gazebo::GazeboRos::GazeboRos ( physics::ModelPtr &  _parent,
sdf::ElementPtr  _sdf,
const std::string &  _plugin 
)
inline

Constructor

Parameters
_parentmodels parent
_sdfsdf to read
_nameof the plugin class

Definition at line 129 of file gazebo_ros_utils.h.

gazebo::GazeboRos::GazeboRos ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf,
const std::string &  _plugin 
)
inline

Constructor

Parameters
_parentsensor parent
_sdfsdf to read
_nameof the plugin class

Definition at line 152 of file gazebo_ros_utils.h.

Member Function Documentation

physics::JointPtr GazeboRos::getJoint ( physics::ModelPtr &  _parent,
const char *  _tag_name,
const std::string &  _joint_default_name 
)

retuns a JointPtr based on an sdf tag_name entry

Parameters
_value
_tag_name
_joint_default_nameJointPtr

Definition at line 130 of file gazebo_ros_utils.cpp.

template<class T >
void gazebo::GazeboRos::getParameter ( T &  _value,
const char *  _tag_name,
const T &  _default 
)
inline

reads the follwoing _tag_name paramer or sets a _default value

Parameters
_value
_tag_name
_defaultsdf tag value

Definition at line 233 of file gazebo_ros_utils.h.

template<class T >
void gazebo::GazeboRos::getParameter ( T &  _value,
const char *  _tag_name 
)
inline

reads the follwoing _tag_name paramer

Parameters
_value
_tag_name
_defaultsdf tag value

Definition at line 249 of file gazebo_ros_utils.h.

template<class T >
void gazebo::GazeboRos::getParameter ( T &  _value,
const char *  _tag_name,
const std::map< std::string, T > &  _options,
const T &  _default 
)
inline

reads the following _tag_name paramer and compares the value with an _options map keys and retuns the corresponding value.

Parameters
_value
_tag_name
_defaultsdf tag value

Definition at line 265 of file gazebo_ros_utils.h.

template<class T >
void gazebo::GazeboRos::getParameter ( T &  _value,
const char *  _tag_name,
const std::map< std::string, T > &  _options 
)
inline

reads the following _tag_name paramer and compares the value with an _options map keys and retuns the corresponding value.

Parameters
_value
_tag_name
_defaultsdf tag value

Definition at line 281 of file gazebo_ros_utils.h.

void GazeboRos::getParameterBoolean ( bool &  _value,
const char *  _tag_name,
const bool &  _default 
)

reads the follwoing _tag_name paramer or sets a _default value

Parameters
_value
_tag_name
_defaultsdf tag value

Definition at line 97 of file gazebo_ros_utils.cpp.

void GazeboRos::getParameterBoolean ( bool &  _value,
const char *  _tag_name 
)

reads the follwoing _tag_name paramer

Parameters
_value
_tag_namesdf tag value

Definition at line 107 of file gazebo_ros_utils.cpp.

const char * GazeboRos::info ( ) const

Returns info text used for log messages

Returns
class name and node name as string

Definition at line 42 of file gazebo_ros_utils.cpp.

void GazeboRos::isInitialized ( )

checks if the ros not is initialized JointPtr

Definition at line 145 of file gazebo_ros_utils.cpp.

boost::shared_ptr< ros::NodeHandle > & GazeboRos::node ( )

returns the initialized created within the constuctor

Returns
rosnode

Definition at line 45 of file gazebo_ros_utils.cpp.

const boost::shared_ptr< ros::NodeHandle > & GazeboRos::node ( ) const

returns the initialized within the constuctor

Returns
rosnode

Definition at line 48 of file gazebo_ros_utils.cpp.

void GazeboRos::readCommonParameter ( )
private

info text for log messages to identify the node

Reads the common plugin parameters used by the constructor

Definition at line 55 of file gazebo_ros_utils.cpp.

std::string GazeboRos::resolveTF ( const std::string &  _name)

resolves a tf frame name by adding the tf_prefix initialized within the constuctor

Parameters
_nameresolved tf name

Definition at line 52 of file gazebo_ros_utils.cpp.

Member Data Documentation

std::string gazebo::GazeboRos::info_text
private

prefix for the ros tf plublisher if not set it uses the namespace_

Definition at line 117 of file gazebo_ros_utils.h.

std::string gazebo::GazeboRos::namespace_
private

name of the plugin class

Definition at line 114 of file gazebo_ros_utils.h.

std::string gazebo::GazeboRos::plugin_
private

sdf to read

Definition at line 113 of file gazebo_ros_utils.h.

boost::shared_ptr<ros::NodeHandle> gazebo::GazeboRos::rosnode_
private

name of the launched node

Definition at line 115 of file gazebo_ros_utils.h.

sdf::ElementPtr gazebo::GazeboRos::sdf_
private

Definition at line 112 of file gazebo_ros_utils.h.

std::string gazebo::GazeboRos::tf_prefix_
private

rosnode

Definition at line 116 of file gazebo_ros_utils.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27