#include <gazebo_ros_utils.h>
|
| 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) |
|
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 105 of file gazebo_ros_utils.h.
gazebo::GazeboRos::GazeboRos |
( |
physics::ModelPtr & |
_parent, |
|
|
sdf::ElementPtr |
_sdf, |
|
|
const std::string & |
_plugin |
|
) |
| |
|
inline |
Constructor
- Parameters
-
_parent | models parent |
_sdf | sdf to read |
_name | of the plugin class |
Definition at line 125 of file gazebo_ros_utils.h.
gazebo::GazeboRos::GazeboRos |
( |
sensors::SensorPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf, |
|
|
const std::string & |
_plugin |
|
) |
| |
|
inline |
Constructor
- Parameters
-
_parent | sensor parent |
_sdf | sdf to read |
_name | of the plugin class |
Definition at line 148 of file gazebo_ros_utils.h.
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_name | JointPtr |
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 | |
_default | sdf tag value |
Definition at line 229 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 | |
_default | sdf tag value |
Definition at line 245 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 | |
_default | sdf tag value |
Definition at line 261 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 | |
_default | sdf tag value |
Definition at line 277 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 | |
_default | sdf 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_name | sdf 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 |
( |
| ) |
|
returns the initialized created within the constuctor
- Returns
- rosnode
Definition at line 45 of file gazebo_ros_utils.cpp.
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
-
Definition at line 52 of file gazebo_ros_utils.cpp.
std::string gazebo::GazeboRos::info_text |
|
private |
prefix for the ros tf plublisher if not set it uses the namespace_
Definition at line 113 of file gazebo_ros_utils.h.
std::string gazebo::GazeboRos::namespace_ |
|
private |
std::string gazebo::GazeboRos::plugin_ |
|
private |
sdf::ElementPtr gazebo::GazeboRos::sdf_ |
|
private |
std::string gazebo::GazeboRos::tf_prefix_ |
|
private |
The documentation for this class was generated from the following files: