00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef GAZEBO_ROS_UTILS_H
00035 #define GAZEBO_ROS_UTILS_H
00036 #include <map>
00037 #include <boost/algorithm/string.hpp>
00038
00039 #include <gazebo/common/common.hh>
00040 #include <gazebo/physics/physics.hh>
00041 #include <gazebo/sensors/Sensor.hh>
00042 #include <ros/ros.h>
00043
00044 namespace gazebo
00045 {
00046
00052 inline std::string GetModelName ( const sensors::SensorPtr &parent )
00053 {
00054 std::string modelName;
00055 std::vector<std::string> values;
00056 std::string scopedName = parent->GetScopedName();
00057 boost::replace_all ( scopedName, "::", "," );
00058 boost::split ( values, scopedName, boost::is_any_of ( "," ) );
00059 if ( values.size() < 2 ) {
00060 modelName = "";
00061 } else {
00062 modelName = values[1];
00063 }
00064 return modelName;
00065 }
00066
00074 inline std::string GetRobotNamespace ( const sensors::SensorPtr &parent, const sdf::ElementPtr &sdf, const char *pInfo = NULL )
00075 {
00076 std::string name_space;
00077 std::stringstream ss;
00078 if ( sdf->HasElement ( "robotNamespace" ) ) {
00079 name_space = sdf->Get<std::string> ( "robotNamespace" );
00080 if ( name_space.empty() ) {
00081 ss << "the 'robotNamespace' param was empty";
00082 name_space = GetModelName ( parent );
00083 } else {
00084 ss << "Using the 'robotNamespace' param: '" << name_space << "'";
00085 }
00086 } else {
00087 ss << "the 'robotNamespace' param did not exit";
00088 }
00089 if ( pInfo != NULL ) {
00090 ROS_INFO ( "%s Plugin (robotNamespace = %s), Info: %s" , pInfo, name_space.c_str(), ss.str().c_str() );
00091 }
00092 return name_space;
00093 }
00094
00100 class GazeboRos
00101 {
00102 private:
00103 sdf::ElementPtr sdf_;
00104 std::string plugin_;
00105 std::string namespace_;
00106 boost::shared_ptr<ros::NodeHandle> rosnode_;
00107 std::string tf_prefix_;
00108 std::string info_text;
00109
00112 void readCommonParameter ();
00113 public:
00120 GazeboRos ( physics::ModelPtr &_parent, sdf::ElementPtr _sdf, const std::string &_plugin )
00121 : sdf_ ( _sdf ), plugin_ ( _plugin ) {
00122 namespace_ = _parent->GetName ();
00123 if ( !sdf_->HasElement ( "robotNamespace" ) ) {
00124 ROS_INFO ( "%s missing <robotNamespace>, defaults is %s", plugin_.c_str(), namespace_.c_str() );
00125 } else {
00126 namespace_ = sdf_->GetElement ( "robotNamespace" )->Get<std::string>();
00127 if ( namespace_.empty() ) {
00128 namespace_ = _parent->GetName();
00129 }
00130 }
00131 if ( !namespace_.empty() )
00132 this->namespace_ += "/";
00133 rosnode_ = boost::shared_ptr<ros::NodeHandle> ( new ros::NodeHandle ( namespace_ ) );
00134 info_text = plugin_ + "(ns = " + namespace_ + ")";
00135 readCommonParameter ();
00136 }
00143 GazeboRos ( sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_plugin )
00144 : sdf_ ( _sdf ), plugin_ ( _plugin ) {
00145
00146 std::stringstream ss;
00147 if ( sdf_->HasElement ( "robotNamespace" ) ) {
00148 namespace_ = sdf_->Get<std::string> ( "robotNamespace" );
00149 if ( namespace_.empty() ) {
00150 ss << "the 'robotNamespace' param was empty";
00151 namespace_ = GetModelName ( _parent );
00152 } else {
00153 ss << "Using the 'robotNamespace' param: '" << namespace_ << "'";
00154 }
00155 } else {
00156 ss << "the 'robotNamespace' param did not exit";
00157 }
00158 info_text = plugin_ + "(ns = " + namespace_ + ")";
00159 ROS_INFO ( "%s: %s" , info_text.c_str(), ss.str().c_str() );
00160 readCommonParameter ();
00161 }
00162
00167 const char* info() const;
00172 boost::shared_ptr<ros::NodeHandle>& node();;
00177 const boost::shared_ptr<ros::NodeHandle>& node() const;
00183 std::string resolveTF ( const std::string &_name );
00184
00192 void getParameterBoolean ( bool &_value, const char *_tag_name, const bool &_default );
00199 void getParameterBoolean ( bool &_value, const char *_tag_name );
00207 physics::JointPtr getJoint ( physics::ModelPtr &_parent, const char *_tag_name, const std::string &_joint_default_name );
00212 void isInitialized();
00213
00214
00222 template <class T>
00223 void getParameter ( T &_value, const char *_tag_name, const T &_default ) {
00224 _value = _default;
00225 if ( !sdf_->HasElement ( _tag_name ) ) {
00226 ROS_WARN ( "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
00227 } else {
00228 this->getParameter<T> ( _value, _tag_name );
00229 }
00230 }
00238 template <class T>
00239 void getParameter ( T &_value, const char *_tag_name ) {
00240 if ( sdf_->HasElement ( _tag_name ) ) {
00241 _value = sdf_->GetElement ( _tag_name )->Get<T>();
00242 }
00243 ROS_DEBUG ( "%s: <%s> = %s", info(), _tag_name, boost::lexical_cast<std::string> ( _value ).c_str() );
00244
00245 }
00246
00254 template <class T>
00255 void getParameter ( T &_value, const char *_tag_name, const std::map<std::string, T> &_options, const T &_default ) {
00256 _value = _default;
00257 if ( !sdf_->HasElement ( _tag_name ) ) {
00258 ROS_WARN ( "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
00259 } else {
00260 this->getParameter<T> ( _value, _tag_name, _options );
00261 }
00262 }
00270 template <class T>
00271 void getParameter ( T &_value, const char *_tag_name, const std::map<std::string, T> &_options ) {
00272 typename std::map<std::string, T >::const_iterator it;
00273 if ( sdf_->HasElement ( _tag_name ) ) {
00274 std::string value = sdf_->GetElement ( _tag_name )->Get<std::string>();
00275 it = _options.find ( value );
00276 if ( it == _options.end() ) {
00277 ROS_WARN ( "%s: <%s> no matching key to %s", info(), _tag_name, value.c_str() );
00278 } else {
00279 _value = it->second;
00280 }
00281 }
00282 ROS_DEBUG ( "%s: <%s> = %s := %s", info(), _tag_name, ( it == _options.end() ?"default":it->first.c_str() ), boost::lexical_cast<std::string> ( _value ).c_str() );
00283 }
00284 };
00285
00286 typedef boost::shared_ptr<GazeboRos> GazeboRosPtr;
00287 }
00288 #endif
00289
00290
00291