GazeboInterface.cpp
Go to the documentation of this file.
00001 #include "GazeboInterface.h"
00002 #include "physics/Model.hh"
00003 #include "physics/Joint.hh"
00004 #include "physics/World.hh"
00005 
00006 #include "nasa_r2_common_msgs/JointStatusArray.h"
00007 
00008 using namespace gazebo;
00009 
00010 GazeboInterface::GazeboInterface()
00011 : ModelPlugin()
00012 , advancedMode(false)
00013 {
00014 }
00015 
00016 GazeboInterface::~GazeboInterface()
00017 {
00018     // shutdown ros
00019     rosNodePtr->shutdown();
00020 }
00021 
00022 void GazeboInterface::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00023 {
00024     // Store the pointer to the model
00025     modelPtr = _model;
00026 
00027     prevStatesUpdateTime = _model->GetWorld()->GetSimTime();
00028     prevStatusUpdateTime = _model->GetWorld()->GetSimTime();
00029 
00030     // create controller
00031     robotControllerPtr.reset(new RobotController(modelPtr));
00032 
00033     // load parameters
00034     std::string robotNamespace = "";
00035     if (_sdf->HasElement("robotNamespace"))
00036     {
00037         robotNamespace = _sdf->GetElement("robotNamespace")->GetValueString() + "/";
00038     }
00039 
00040     std::string paramsNamespace = "";
00041     if (_sdf->HasElement("paramsNamespace"))
00042     {
00043         paramsNamespace = _sdf->GetElement("paramsNamespace")->GetValueString() + "/";
00044     }
00045 
00046     if (!_sdf->HasElement("jointCommandsTopic"))
00047     {
00048         ROS_FATAL("GazeboInterface plugin missing <jointCommandsTopic>, cannot proceed");
00049         return;
00050     }
00051     else
00052         jointCommandsTopic = _sdf->GetElement("jointCommandsTopic")->GetValueString();
00053 
00054     if (!_sdf->HasElement("jointStatesTopic"))
00055     {
00056         ROS_FATAL("GazeboInterface plugin missing <jointStatesTopic>, cannot proceed");
00057         return;
00058     }
00059     else
00060         jointStatesTopic = _sdf->GetElement("jointStatesTopic")->GetValueString();
00061 
00062     if (!_sdf->HasElement("jointCapabilitiesTopic"))
00063     {
00064         ROS_FATAL("GazeboInterface plugin missing <jointCapabilitiesTopic>, cannot proceed");
00065         return;
00066     }
00067     else
00068         jointCapabilitiesTopic = _sdf->GetElement("jointCapabilitiesTopic")->GetValueString();
00069 
00070     if (!_sdf->HasElement("jointStatesRate"))
00071     {
00072         jointStatesStepTime = 0.;
00073     }
00074     else
00075         jointStatesStepTime = 1./_sdf->GetElement("jointStatesRate")->GetValueDouble();
00076 
00077     if (!_sdf->HasElement("jointCommandRefsTopic"))
00078     {
00079         ROS_FATAL("GazeboInterface plugin missing <jointCommandRefsTopic>, cannot proceed");
00080         return;
00081     }
00082     else
00083         jointCommandRefsTopic = _sdf->GetElement("jointCommandRefsTopic")->GetValueString();
00084 
00085     if (!_sdf->HasElement("advancedMode"))
00086     {
00087         ROS_INFO("GazeboInterface plugin missing <advancedMode>, defaults to false");
00088         advancedMode = false;
00089     }
00090     else
00091     {
00092         std::string strVal = _sdf->GetElement("advancedMode")->GetValueString();
00093         if (strVal == "1")
00094             advancedMode = true;
00095         else if (strVal == "0")
00096             advancedMode = false;
00097         else
00098         {
00099             ROS_WARN("GazeboInterface plugin <advancedMode> should be type bool (true/false), defaults to false");
00100             advancedMode = false;
00101         }
00102     }
00103 
00104     ROS_INFO("GazeboInterface plugin advancedMode: %s", advancedMode ? "true" : "false");
00105 
00106     if (advancedMode)
00107     {
00108         if (!_sdf->HasElement("jointControlTopic"))
00109         {
00110             ROS_FATAL("GazeboInterface plugin missing <jointControlTopic>, cannot proceed");
00111             return;
00112         }
00113         else
00114             jointControlTopic = _sdf->GetElement("jointControlTopic")->GetValueString();
00115 
00116         if (!_sdf->HasElement("jointStatusTopic"))
00117         {
00118             ROS_FATAL("GazeboInterface plugin missing <jointStatusTopic>, cannot proceed");
00119             return;
00120         }
00121         else
00122             jointStatusTopic = _sdf->GetElement("jointStatusTopic")->GetValueString();
00123 
00124         if (!_sdf->HasElement("jointStatusRate"))
00125         {
00126             jointStatusStepTime = 0.;
00127         }
00128         else
00129             jointStatusStepTime = 1./_sdf->GetElement("jointStatusRate")->GetValueDouble();
00130     }
00131 
00132     // create ros nodes
00133     rosNodePtr.reset(new ros::NodeHandle(robotNamespace));
00134     paramsNodePtr.reset(new ros::NodeHandle(paramsNamespace));
00135 
00136     // Listen to the update event. This event is broadcast every
00137     // simulation iteration.
00138     updateConnectionPtr = event::Events::ConnectWorldUpdateStart(boost::bind(&GazeboInterface::update, this));
00139 
00140     ROS_INFO("Gazebo Interface plugin loaded");
00141 }
00142 
00143 void GazeboInterface::traverseParams(XmlRpc::XmlRpcValue param, std::map<std::string, XmlRpc::XmlRpcValue>& valMap, std::string searchKey,
00144                     std::string ns, std::string name)
00145 {
00146     std::string fullName;
00147     if (name.empty())
00148     {
00149         fullName = ns;
00150     }
00151     else
00152     {
00153         fullName = ns + "/" + name;
00154     }
00155 
00156     if (param.getType() == XmlRpc::XmlRpcValue::TypeStruct)
00157     {
00158         // if it is a struct, recurse
00159         for (XmlRpc::XmlRpcValue::iterator paramIt = param.begin(); paramIt != param.end(); ++paramIt)
00160         {
00161             traverseParams(paramIt->second, valMap, searchKey, fullName, paramIt->first);
00162         }
00163     }
00164     else if (searchKey == "")
00165     {
00166         // if there is no search key, add to map with fully qualified name
00167         valMap.insert(std::make_pair(fullName, param));
00168     }
00169     else if (searchKey == name)
00170     {
00171         // if the searchKey matches the name, add to map omitting searchKey
00172         valMap.insert(std::make_pair(ns, param));
00173     }
00174 
00175     // if searchKey is not matched, the function does nothing
00176 }
00177 
00178 bool GazeboInterface::getDoubleVal(XmlRpc::XmlRpcValue& val, double& doubleVal)
00179 {
00180     if (val.getType() == XmlRpc::XmlRpcValue::TypeInt)
00181     {
00182         doubleVal = (double)(int)val;
00183     }
00184     else if (val.getType() == XmlRpc::XmlRpcValue::TypeDouble)
00185     {
00186         doubleVal = (double)val;
00187     }
00188     else
00189     {
00190         return false;
00191     }
00192 
00193     return true;
00194 }
00195 
00196 void GazeboInterface::Init()
00197 {
00198     ROS_DEBUG("add joints");
00199     // add all joints to controller
00200     for (unsigned int i = 0; i < modelPtr->GetJointCount(); ++i)
00201     {
00202         physics::JointPtr jPtr = modelPtr->GetJoint(i);
00203         robotControllerPtr->addJoint(jPtr, advancedMode);
00204         ROS_DEBUG("Add %s to controller", jPtr->GetName().c_str());
00205     }
00206 
00207     XmlRpc::XmlRpcValue param;
00208     // set joint dependencies
00209     if (paramsNodePtr->getParam("dependency", param))
00210     {
00211         ROS_DEBUG("set dependencies");
00212         // get dependent children
00213         std::map<std::string, XmlRpc::XmlRpcValue> dependentChildrenMap;
00214         traverseParams(param, dependentChildrenMap, "children");
00215         // get dependent factors
00216         std::map<std::string, XmlRpc::XmlRpcValue> dependentFactorsMap;
00217         traverseParams(param, dependentFactorsMap, "factors");
00218 
00219         // iterate through and add dependencies
00220         for (std::map<std::string, XmlRpc::XmlRpcValue>::iterator depIt = dependentChildrenMap.begin();
00221              depIt != dependentChildrenMap.end(); ++depIt)
00222         {
00223             XmlRpc::XmlRpcValue factorVal = dependentFactorsMap[depIt->first];
00224             // value can be a string or an array of strings
00225             if (depIt->second.getType() == XmlRpc::XmlRpcValue::TypeString)
00226             {
00227                 double val;
00228                 if (getDoubleVal(factorVal, val))
00229                 {
00230                     // child, parent, factor
00231                     ROS_DEBUG("Add joint dependency: %s, %s, %f", ((std::string)depIt->second).c_str(), depIt->first.c_str(), (double)factorVal);
00232                     robotControllerPtr->addJointDependency((std::string)depIt->second, depIt->first, (double)factorVal);
00233                 }
00234                 else
00235                 {
00236                     ROS_WARN("Add dependency for %s (child) to %s (parent) not completed because factor not an appropriate type (double or int)",
00237                              ((std::string)depIt->second).c_str(), depIt->first.c_str());
00238                 }
00239             }
00240             else if (depIt->second.getType() == XmlRpc::XmlRpcValue::TypeArray)
00241             {
00242                 if (factorVal.getType() == XmlRpc::XmlRpcValue::TypeArray && factorVal.size() == depIt->second.size())
00243                 {
00244                     for (int i = 0; i < depIt->second.size(); ++i)
00245                     {
00246                         if (depIt->second[i].getType() == XmlRpc::XmlRpcValue::TypeString)
00247                         {
00248                             double val;
00249                             if (getDoubleVal(factorVal[i], val))
00250                             {
00251                                 // child, parent, factor
00252                                 ROS_DEBUG("Add joint dependency: %s, %s, %f", ((std::string)depIt->second[i]).c_str(), depIt->first.c_str(), val);
00253                                 robotControllerPtr->addJointDependency((std::string)depIt->second[i], depIt->first, val);
00254                             }
00255                             else
00256                             {
00257                                 ROS_WARN("Add dependency for %s (child) to %s (parent) not completed because factor not an appropriate type (double or int)",
00258                                          ((std::string)depIt->second[i]).c_str(), depIt->first.c_str());
00259                             }
00260                         }
00261                         else
00262                         {
00263                             ROS_WARN("A dependency to %s (parent) not added because type is invalid", depIt->first.c_str());
00264                         }
00265                     }
00266                 }
00267                 else
00268                 {
00269                     ROS_WARN("Add dependency to %s (parent) not completed because children/factors array size not the same",
00270                              depIt->first.c_str());
00271                 }
00272             }
00273         }
00274     }
00275 
00276     // get initial positions
00277     if (paramsNodePtr->getParam("initial_position", param))
00278     {
00279         ROS_DEBUG("set initial positions");
00280         bool radians = true;
00281         if (param.hasMember("radians") && param["radians"].getType() == XmlRpc::XmlRpcValue::TypeBoolean)
00282         {
00283             radians = (bool)param["radians"];
00284             ROS_DEBUG("radians: %d", radians);
00285         }
00286         else
00287         {
00288             ROS_WARN("No 'radians' member provided (or invalid type) in 'initial_position'; assumed true");
00289         }
00290 
00291         std::map<std::string, XmlRpc::XmlRpcValue> initialPoseMapParams;
00292         traverseParams(param, initialPoseMapParams);
00293         // remove '/radians'
00294         initialPoseMapParams.erase("/radians");
00295 
00296         // get positions
00297         std::map<std::string, double> initialPoseMap;
00298         for (std::map<std::string, XmlRpc::XmlRpcValue>::iterator poseIt = initialPoseMapParams.begin();
00299              poseIt != initialPoseMapParams.end(); ++poseIt)
00300         {
00301             double val;
00302             if (getDoubleVal(poseIt->second, val))
00303             {
00304                 if (radians == false)
00305                 {
00306                     val = GZ_DTOR(val);
00307                 }
00308 
00309                 if (modelPtr->GetJoint(poseIt->first))
00310                 {
00311                     initialPoseMap.insert(std::make_pair(poseIt->first, val));
00312                     ROS_DEBUG("initial position of %s set to %f", poseIt->first.c_str(), val);
00313                 }
00314                 else
00315                 {
00316                     ROS_INFO("initial position of %s ignored because model doesn't contain joint", poseIt->first.c_str());
00317                 }
00318             }
00319             else
00320             {
00321                 ROS_WARN("Sim initial position value (%s) ignored because it is not a valid type (double or int)", poseIt->first.c_str());
00322             }
00323         }
00324 
00325         // set positions
00326         robotControllerPtr->setJointPositions(initialPoseMap);
00327     }
00328 
00329     // get position PIDsmodelPtr->GetWorld()->GetSimTime()
00330     if (paramsNodePtr->getParam("position_pid", param))
00331     {
00332         ROS_DEBUG("set position PIDs");
00333         std::map<std::string, XmlRpc::XmlRpcValue> positionPidMap;
00334         traverseParams(param, positionPidMap);
00335 
00336         // iterate through and add PIDs
00337         for (std::map<std::string, XmlRpc::XmlRpcValue>::iterator pidIt = positionPidMap.begin();
00338              pidIt != positionPidMap.end(); ++pidIt)
00339         {
00340             if (pidIt->second.getType() == XmlRpc::XmlRpcValue::TypeArray && pidIt->second.size() >= 3)
00341             {
00342                 std::vector<double> gains(7, 0.0);
00343                 bool valid = true;
00344                 for (int i = 0; i < pidIt->second.size(); ++ i)
00345                 {
00346                     valid &= getDoubleVal(pidIt->second[i], gains[i]);
00347                 }
00348 
00349                 if (valid)
00350                 {
00351                     ROS_DEBUG("setPosPid: %s, %f, %f, %f, %f, %f, %f, %f", pidIt->first.c_str(), gains[0], gains[1], gains[2], gains[3], gains[4], gains[5], gains[6]);
00352                     robotControllerPtr->setPosPid(pidIt->first, gains[0], gains[1], gains[2], gains[3], gains[4], gains[5], gains[6]);
00353                 }
00354                 else
00355                 {
00356                     ROS_WARN("position PID for %s not set because the values are not valid (double or int)", pidIt->first.c_str());
00357                 }
00358             }
00359             else
00360             {
00361                 ROS_WARN("position PID values for %s not set because it is not an array of size 3 or greater", pidIt->first.c_str());
00362             }
00363         }
00364     }
00365 
00366     // get velocity PIDs
00367     if (paramsNodePtr->getParam("velocity_pid", param))
00368     {
00369         ROS_DEBUG("set velocity PIDs");
00370         std::map<std::string, XmlRpc::XmlRpcValue> velocityPidMap;
00371         traverseParams(param, velocityPidMap);
00372 
00373         // iterate through and add PIDs
00374         for (std::map<std::string, XmlRpc::XmlRpcValue>::iterator pidIt = velocityPidMap.begin();
00375              pidIt != velocityPidMap.end(); ++pidIt)
00376         {
00377             if (pidIt->second.getType() == XmlRpc::XmlRpcValue::TypeArray && pidIt->second.size() >= 3)
00378             {
00379                 std::vector<double> gains(7, 0.0);
00380                 bool valid = true;
00381                 for (int i = 0; i < pidIt->second.size(); ++ i)
00382                 {
00383                     valid &= getDoubleVal(pidIt->second[i], gains[i]);
00384                 }
00385 
00386                 if (valid)
00387                 {
00388                     ROS_DEBUG("setVelPid: %s, %f, %f, %f, %f, %f, %f, %f", pidIt->first.c_str(), gains[0], gains[1], gains[2], gains[3], gains[4], gains[5], gains[6]);
00389                     robotControllerPtr->setVelPid(pidIt->first, gains[0], gains[1], gains[2], gains[3], gains[4], gains[5], gains[6]);
00390                 }
00391                 else
00392                 {
00393                     ROS_WARN("velocity PID for %s not set because the values are not valid (double or int)", pidIt->first.c_str());
00394                 }
00395             }
00396             else
00397             {
00398                 ROS_WARN("velocity PID values for %s not set because it is not an array of size 3 or greater", pidIt->first.c_str());
00399             }
00400         }
00401     }
00402 
00403     // if not in advanced mode, tell the controller to hold the joint positions
00404     if (!advancedMode)
00405     {
00406         for (unsigned int i = 0; i < modelPtr->GetJointCount(); ++i)
00407         {
00408             physics::JointPtr jPtr = modelPtr->GetJoint(i);
00409             robotControllerPtr->setJointPosTarget(jPtr->GetName(), jPtr->GetAngle(0).GetAsRadian());
00410         }
00411     }
00412 
00413     // subscribe to ROS joint commands
00414     jointCommandsSub  = rosNodePtr->subscribe(jointCommandsTopic,  5, &GazeboInterface::commandJoints,  this);
00415 
00416     // advertise joint state publishing
00417     jointStatePub = rosNodePtr->advertise<sensor_msgs::JointState>(jointStatesTopic, true);
00418 
00419     // advertise joint capabilities publishing
00420     jointCapabilitiesPub = rosNodePtr->advertise<nasa_r2_common_msgs::JointCapability>(jointCapabilitiesTopic, true);
00421 
00422     // advertise joint command ref publishing
00423     jointCommandRefsPub = rosNodePtr->advertise<nasa_r2_common_msgs::JointCommand>(jointCommandRefsTopic, true);
00424 
00425     if (advancedMode)
00426     {
00427         // subscribe to ROS joint control messages
00428         jointControlSub  = rosNodePtr->subscribe(jointControlTopic,  5, &GazeboInterface::controlJoints,  this);
00429 
00430         // advertise joint status publishing
00431         jointStatusPub = rosNodePtr->advertise<nasa_r2_common_msgs::JointStatusArray>(jointStatusTopic, true);
00432     }
00433 
00434     ROS_INFO("Gazebo Interface plugin initialized");
00435 }
00436 
00437 void GazeboInterface::update()
00438 {
00439     common::Time currTime = modelPtr->GetWorld()->GetSimTime();
00440 
00441     // update joint controller
00442     robotControllerPtr->update();
00443 
00444     //publish joint states
00445     if ((currTime - prevStatesUpdateTime).Double() >= jointStatesStepTime)
00446     {
00447         prevStatesUpdateTime = currTime;
00448         sensor_msgs::JointStatePtr msgPtr(new sensor_msgs::JointState);
00449         nasa_r2_common_msgs::JointCommandPtr refPtr(new nasa_r2_common_msgs::JointCommand);
00450         nasa_r2_common_msgs::JointCapabilityPtr capPtr(new nasa_r2_common_msgs::JointCapability);
00451         msgPtr->header.stamp = ros::Time::now();
00452         refPtr->header.stamp = ros::Time::now();
00453 
00454         // get positions
00455         robotControllerPtr->getJointStates(jointStates);
00456 
00457         // build position message
00458         for (std::map<std::string, RobotController::JointState>::const_iterator stateIt = jointStates.begin(); stateIt != jointStates.end(); ++stateIt)
00459         {
00460             std::string::size_type index = stateIt->first.find("fixed");
00461             if (index != std::string::npos)
00462             {
00463                 continue;
00464             }
00465             index = stateIt->first.find("/joint");
00466             if (index != std::string::npos)
00467             {
00468                 std::string name = stateIt->first;
00469                 msgPtr->name.push_back(name);
00470                 msgPtr->position.push_back(stateIt->second.position);
00471                 msgPtr->velocity.push_back(stateIt->second.velocity);
00472                 msgPtr->effort.push_back(stateIt->second.effort);
00473             }
00474             else
00475             {
00476                 msgPtr->name.push_back(stateIt->first);
00477                 msgPtr->position.push_back(stateIt->second.position);
00478                 msgPtr->velocity.push_back(stateIt->second.velocity);
00479                 msgPtr->effort.push_back(stateIt->second.effort);
00480             }
00481         }
00482 
00483         // get targets
00484         robotControllerPtr->getJointTargets(jointCommandRefs);
00485 
00486         // build targets message
00487         for (std::map<std::string, RobotController::JointState>::const_iterator refsIt = jointCommandRefs.begin(); refsIt != jointCommandRefs.end(); ++refsIt)
00488         {
00489             std::string::size_type index = refsIt->first.find("fixed");
00490             if (index == std::string::npos)
00491             {
00492                 refPtr->name.push_back(refsIt->first);
00493                 refPtr->desiredPosition.push_back(refsIt->second.position);
00494                 refPtr->desiredPositionVelocityLimit.push_back(refsIt->second.velocity);
00495                 refPtr->feedForwardTorque.push_back(refsIt->second.effort);
00496                 refPtr->proportionalGain.push_back(0);
00497                 refPtr->derivativeGain.push_back(0);
00498                 refPtr->integralGain.push_back(0);
00499                 refPtr->positionLoopTorqueLimit.push_back(0);
00500                 refPtr->positionLoopWindupLimit.push_back(0);
00501                 refPtr->torqueLoopVelocityLimit.push_back(0);
00502             }
00503         }
00504 
00505         // get capabilities
00506         robotControllerPtr->getJointLimits(jointLimits);
00507 
00508         // build capability message
00509         for (std::map<std::string, std::pair<double, double> >::const_iterator limsIt = jointLimits.begin(); limsIt != jointLimits.end(); ++limsIt)
00510         {
00511             std::string::size_type index = limsIt->first.find("fixed");
00512             if (index == std::string::npos)
00513             {
00514                 capPtr->name.push_back(limsIt->first);
00515                 capPtr->positionLimitMax.push_back(limsIt->second.second);
00516                 capPtr->positionLimitMin.push_back(limsIt->second.first);
00517                 capPtr->torqueLimit.push_back(1000.);
00518             }
00519         }
00520 
00521         jointCommandRefsPub.publish(refPtr);
00522         jointStatePub.publish(msgPtr);
00523         //jointCommandRefsPub.publish(refPtr);
00524         jointCapabilitiesPub.publish(capPtr);
00525     }
00526 
00527     //publish joint status
00528     if (advancedMode && (currTime - prevStatusUpdateTime).Double() >= jointStatusStepTime)
00529     {
00530         prevStatusUpdateTime = currTime;
00531         robotControllerPtr->publishJointStatuses(jointStatusPub);
00532     }
00533 }
00534 
00535 void GazeboInterface::commandJoints(const sensor_msgs::JointState::ConstPtr& msg)
00536 {
00537     bool setPos = msg->position.size() >= msg->name.size();
00538     bool setVel  = msg->velocity.size() >= msg->name.size();
00539     bool setEffort  = msg->effort.size() >= msg->name.size();
00540 
00541     ROS_DEBUG("GazeboInterface received joint command");
00542     for (unsigned int i = 0; i < msg->name.size(); ++i)
00543     {
00544         if (setPos)
00545         {
00546             robotControllerPtr->setJointPosTarget(msg->name[i], msg->position[i]);
00547         }
00548         else if (setEffort)
00549         {
00550             robotControllerPtr->setJointEffortTarget(msg->name[i], msg->effort[i]);
00551         }
00552         else if (setVel)
00553         {
00554             robotControllerPtr->setJointVelTarget(msg->name[i], msg->velocity[i]);
00555         }
00556     }
00557 }
00558 
00559 // handle control message
00560 void GazeboInterface::controlJoints(const nasa_r2_common_msgs::JointControl::ConstPtr& msg)
00561 {
00562     ROS_DEBUG("GazeboInterface received joint control");
00563     robotControllerPtr->setJointControl(msg);
00564 }
00565 
00566 GZ_REGISTER_MODEL_PLUGIN(GazeboInterface)


gazebo_interface
Author(s): rctaylo2
autogenerated on Mon Oct 6 2014 02:44:38