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 <gazebo/gazebo_config.h>
00043 #include <ros/ros.h>
00044
00045 #ifndef GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
00046 # if GAZEBO_MAJOR_VERSION >= 7
00047 #define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST using std::dynamic_pointer_cast
00048 # else
00049 #define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST using boost::dynamic_pointer_cast
00050 # endif
00051 #endif
00052
00053 namespace gazebo
00054 {
00055
00061 inline std::string GetModelName ( const sensors::SensorPtr &parent )
00062 {
00063 std::string modelName;
00064 std::vector<std::string> values;
00065 # if GAZEBO_MAJOR_VERSION >= 7
00066 std::string scopedName = parent->ScopedName();
00067 # else
00068 std::string scopedName = parent->GetScopedName();
00069 #endif
00070 boost::replace_all ( scopedName, "::", "," );
00071 boost::split ( values, scopedName, boost::is_any_of ( "," ) );
00072 if ( values.size() < 2 ) {
00073 modelName = "";
00074 } else {
00075 modelName = values[1];
00076 }
00077 return modelName;
00078 }
00079
00087 inline std::string GetRobotNamespace ( const sensors::SensorPtr &parent, const sdf::ElementPtr &sdf, const char *pInfo = NULL )
00088 {
00089 std::string name_space;
00090 std::stringstream ss;
00091 if ( sdf->HasElement ( "robotNamespace" ) ) {
00092 name_space = sdf->Get<std::string> ( "robotNamespace" );
00093 if ( name_space.empty() ) {
00094 ss << "the 'robotNamespace' param was empty";
00095 name_space = GetModelName ( parent );
00096 } else {
00097 ss << "Using the 'robotNamespace' param: '" << name_space << "'";
00098 }
00099 } else {
00100 ss << "the 'robotNamespace' param did not exit";
00101 }
00102 if ( pInfo != NULL ) {
00103 ROS_INFO ( "%s Plugin (robotNamespace = %s), Info: %s" , pInfo, name_space.c_str(), ss.str().c_str() );
00104 }
00105 return name_space;
00106 }
00107
00113 class GazeboRos
00114 {
00115 private:
00116 sdf::ElementPtr sdf_;
00117 std::string plugin_;
00118 std::string namespace_;
00119 boost::shared_ptr<ros::NodeHandle> rosnode_;
00120 std::string tf_prefix_;
00121 std::string info_text;
00122
00125 void readCommonParameter ();
00126 public:
00133 GazeboRos ( physics::ModelPtr &_parent, sdf::ElementPtr _sdf, const std::string &_plugin )
00134 : sdf_ ( _sdf ), plugin_ ( _plugin ) {
00135 namespace_ = _parent->GetName ();
00136 if ( !sdf_->HasElement ( "robotNamespace" ) ) {
00137 ROS_INFO ( "%s missing <robotNamespace>, defaults is %s", plugin_.c_str(), namespace_.c_str() );
00138 } else {
00139 namespace_ = sdf_->GetElement ( "robotNamespace" )->Get<std::string>();
00140 if ( namespace_.empty() ) {
00141 namespace_ = _parent->GetName();
00142 }
00143 }
00144 if ( !namespace_.empty() )
00145 this->namespace_ += "/";
00146 rosnode_ = boost::shared_ptr<ros::NodeHandle> ( new ros::NodeHandle ( namespace_ ) );
00147 info_text = plugin_ + "(ns = " + namespace_ + ")";
00148 readCommonParameter ();
00149 }
00156 GazeboRos ( sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_plugin )
00157 : sdf_ ( _sdf ), plugin_ ( _plugin ) {
00158
00159 std::stringstream ss;
00160 if ( sdf_->HasElement ( "robotNamespace" ) ) {
00161 namespace_ = sdf_->Get<std::string> ( "robotNamespace" );
00162 if ( namespace_.empty() ) {
00163 ss << "the 'robotNamespace' param was empty";
00164 namespace_ = GetModelName ( _parent );
00165 } else {
00166 ss << "Using the 'robotNamespace' param: '" << namespace_ << "'";
00167 }
00168 } else {
00169 ss << "the 'robotNamespace' param did not exit";
00170 }
00171 rosnode_ = boost::shared_ptr<ros::NodeHandle> ( new ros::NodeHandle ( namespace_ ) );
00172 info_text = plugin_ + "(ns = " + namespace_ + ")";
00173 ROS_INFO ( "%s: %s" , info_text.c_str(), ss.str().c_str() );
00174 readCommonParameter ();
00175 }
00176
00181 const char* info() const;
00186 boost::shared_ptr<ros::NodeHandle>& node();;
00191 const boost::shared_ptr<ros::NodeHandle>& node() const;
00197 std::string resolveTF ( const std::string &_name );
00198
00206 void getParameterBoolean ( bool &_value, const char *_tag_name, const bool &_default );
00213 void getParameterBoolean ( bool &_value, const char *_tag_name );
00221 physics::JointPtr getJoint ( physics::ModelPtr &_parent, const char *_tag_name, const std::string &_joint_default_name );
00226 void isInitialized();
00227
00228
00236 template <class T>
00237 void getParameter ( T &_value, const char *_tag_name, const T &_default ) {
00238 _value = _default;
00239 if ( !sdf_->HasElement ( _tag_name ) ) {
00240 ROS_WARN ( "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
00241 } else {
00242 this->getParameter<T> ( _value, _tag_name );
00243 }
00244 }
00252 template <class T>
00253 void getParameter ( T &_value, const char *_tag_name ) {
00254 if ( sdf_->HasElement ( _tag_name ) ) {
00255 _value = sdf_->GetElement ( _tag_name )->Get<T>();
00256 }
00257 ROS_DEBUG ( "%s: <%s> = %s", info(), _tag_name, boost::lexical_cast<std::string> ( _value ).c_str() );
00258
00259 }
00260
00268 template <class T>
00269 void getParameter ( T &_value, const char *_tag_name, const std::map<std::string, T> &_options, const T &_default ) {
00270 _value = _default;
00271 if ( !sdf_->HasElement ( _tag_name ) ) {
00272 ROS_WARN ( "%s: missing <%s> default is %s", info(), _tag_name, boost::lexical_cast<std::string> ( _default ).c_str() );
00273 } else {
00274 this->getParameter<T> ( _value, _tag_name, _options );
00275 }
00276 }
00284 template <class T>
00285 void getParameter ( T &_value, const char *_tag_name, const std::map<std::string, T> &_options ) {
00286 typename std::map<std::string, T >::const_iterator it;
00287 if ( sdf_->HasElement ( _tag_name ) ) {
00288 std::string value = sdf_->GetElement ( _tag_name )->Get<std::string>();
00289 it = _options.find ( value );
00290 if ( it == _options.end() ) {
00291 ROS_WARN ( "%s: <%s> no matching key to %s", info(), _tag_name, value.c_str() );
00292 } else {
00293 _value = it->second;
00294 }
00295 }
00296 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() );
00297 }
00298 };
00299
00300 typedef boost::shared_ptr<GazeboRos> GazeboRosPtr;
00301 }
00302 #endif
00303
00304
00305