00001 #include "../include/RobotController.h"
00002 
00003 #include "physics/Model.hh"
00004 #include "physics/World.hh"
00005 #include "physics/Joint.hh"
00006 #include "physics/Link.hh"
00007 
00008 #include <ros/ros.h>
00009 
00010 #include "r2_msgs/JointStatusArray.h"
00011 
00012 using namespace gazebo;
00013 
00014 RobotController::RobotController(physics::ModelPtr _modelPtr)
00015 : modelPtr(_modelPtr)
00016 {
00017     prevUpdateTime = _modelPtr->GetWorld()->GetSimTime();
00018 }
00019 
00020 RobotController::~RobotController()
00021 {
00022 }
00023 
00024 void RobotController::addJoint(physics::JointPtr _jointPtr, bool advancedMode)
00025 {
00026     boost::mutex::scoped_lock(pidMutex);
00027     JointControllerPtr jointPtr(new JointController(_jointPtr, advancedMode));
00028     joints[_jointPtr->GetName()] = jointPtr;
00029 }
00030 
00031 void RobotController::addJointDependency(std::string _childName, std::string _parentName, double factor)
00032 {
00033     if (joints.find(_parentName) == joints.end())
00034     {
00035         ROS_WARN("GazeboInterface joint dependency not set because parent (%s) not found", _parentName.c_str());
00036         return;
00037     }
00038     if (joints.find(_childName) == joints.end())
00039     {
00040         ROS_WARN("GazeboInterface joint dependency not set because child (%s) not found", _childName.c_str());
00041         return;
00042     }
00043     boost::mutex::scoped_lock(pidMutex);
00044     dependencies.insert(std::make_pair(_parentName, std::make_pair(_childName, factor)));
00045 }
00046 
00047 void RobotController::setPosPid(const std::string& name, double _p, double _i, double _d,
00048                                   double _imax, double _imin, double _cmdMax, double _cmdMin)
00049 {
00050     if (joints.find(name) == joints.end())
00051     {
00052         ROS_WARN("GazeboInterface PosPID not set because joint (%s) not found", name.c_str());
00053         return;
00054     }
00055     boost::mutex::scoped_lock(pidMutex);
00056     joints[name]->setPosPid(_p, _i, _d, _imax, _imin, _cmdMax, _cmdMin);
00057 }
00058 
00059 void RobotController::setVelPid(const std::string& name, double _p, double _i, double _d,
00060                                   double _imax, double _imin, double _cmdMax, double _cmdMin)
00061 {
00062     if (joints.find(name) == joints.end())
00063     {
00064         ROS_WARN("GazeboInterface PosPID not set because joint (%s) not found", name.c_str());
00065         return;
00066     }
00067     boost::mutex::scoped_lock(pidMutex);
00068     joints[name]->setVelPid(_p, _i, _d, _imax, _imin, _cmdMax, _cmdMin);
00069 }
00070 
00071 
00072 void RobotController::setJointPositions(std::map<std::string, double> posMap)
00073 {
00074     
00075     bool is_paused = modelPtr->GetWorld()->IsPaused();
00076     if (!is_paused) modelPtr->GetWorld()->SetPaused(true);
00077 
00078     
00079     std::map<std::string, bool> brakeStates;
00080     for (std::map<std::string, JointControllerPtr>::iterator it = joints.begin(); it != joints.end(); ++it)
00081     {
00082         brakeStates[it->first] = it->second->getJointStatus().brakeReleased;
00083         it->second->releaseBrake();
00084     }
00085 
00086     
00087     for (std::map<std::string, double>::iterator posIt = posMap.begin(); posIt != posMap.end(); ++posIt)
00088     {
00089         std::pair<dependenciesType::iterator, dependenciesType::iterator> deps = dependencies.equal_range(posIt->first);
00090         for (dependenciesType::iterator depIt = deps.first; depIt != deps.second; ++depIt)
00091         {
00092             posMap[depIt->second.first] = depIt->second.second * posIt->second;
00093         }
00094     }
00095 
00096     
00097     modelPtr->SetJointPositions(posMap);
00098 
00099     
00100     for (std::map<std::string, bool>::iterator it = brakeStates.begin(); it != brakeStates.end(); ++it)
00101     {
00102         joints[it->first]->releaseBrake(it->second);
00103     }
00104 
00105     
00106     modelPtr->GetWorld()->SetPaused(is_paused);
00107 }
00108 
00109 void RobotController::setJointPosTarget(const std::string& name, double target)
00110 {
00111     if (joints.find(name) == joints.end())
00112     {
00113         ROS_WARN("GazeboInterface setJointPosTarget not set because joint (%s) not found", name.c_str());
00114         return;
00115     }
00116     boost::mutex::scoped_lock(pidMutex);
00117     joints[name]->setPosTarget(target);
00118 
00119     
00120     std::pair<dependenciesType::iterator, dependenciesType::iterator> deps = dependencies.equal_range(name);
00121     for (dependenciesType::iterator depIt = deps.first; depIt != deps.second; ++depIt)
00122     {
00123         joints[depIt->second.first]->setPosTarget(depIt->second.second * target);
00124     }
00125 }
00126 
00127 void RobotController::setJointVelTarget(const std::string& name, double target)
00128 {
00129     if (joints.find(name) == joints.end())
00130     {
00131         ROS_WARN("GazeboInterface setJointVelTarget not set because joint (%s) not found", name.c_str());
00132         return;
00133     }
00134     boost::mutex::scoped_lock(pidMutex);
00135     joints[name]->setVelTarget(target);
00136 
00137     
00138     std::pair<dependenciesType::iterator, dependenciesType::iterator> deps = dependencies.equal_range(name);
00139     for (dependenciesType::iterator depIt = deps.first; depIt != deps.second; ++depIt)
00140     {
00141         joints[depIt->second.first]->setVelTarget(depIt->second.second * target);
00142     }
00143 }
00144 
00145 void RobotController::setJointEffortTarget(const std::string& name, double target)
00146 {
00147     if (joints.find(name) == joints.end())
00148     {
00149         ROS_WARN("GazeboInterface setJointEffortTarget not set because joint (%s) not found", name.c_str());
00150         return;
00151     }
00152     boost::mutex::scoped_lock(pidMutex);
00153     joints[name]->setEffortTarget(target);
00154 
00155     
00156     std::pair<dependenciesType::iterator, dependenciesType::iterator> deps = dependencies.equal_range(name);
00157     for (dependenciesType::iterator depIt = deps.first; depIt != deps.second; ++depIt)
00158     {
00159         joints[depIt->second.first]->setEffortTarget(depIt->second.second * target);
00160     }
00161 }
00162 
00163 
00164 void RobotController::setJointControl(const r2_msgs::JointControl::ConstPtr& msg)
00165 {
00166     if (joints.find(msg->joint) == joints.end())
00167     {
00168         ROS_WARN("GazeboInterface setJointControl not set because joint (%s) not found", msg->joint.c_str());
00169         return;
00170     }
00171     boost::mutex::scoped_lock(pidMutex);
00172     joints[msg->joint]->setJointControl(msg);
00173 
00174     
00175     std::pair<dependenciesType::iterator, dependenciesType::iterator> deps = dependencies.equal_range(msg->joint);
00176     for (dependenciesType::iterator depIt = deps.first; depIt != deps.second; ++depIt)
00177     {
00178         r2_msgs::JointControl* jcPtr = new r2_msgs::JointControl(*msg);
00179         jcPtr->joint = depIt->second.first;
00180         r2_msgs::JointControl::ConstPtr depJointControlPtr(jcPtr);
00181         joints[depIt->second.first]->setJointControl(depJointControlPtr);
00182     }
00183 }
00184 
00185 const r2_msgs::JointStatus& RobotController::getJointStatus(const std::string& name) const
00186 {
00187     std::map<std::string, JointControllerPtr>::const_iterator cit = joints.find(name);
00188     if (cit == joints.end())
00189     {
00190         ROS_WARN("GazeboInterface getJointStatus failed because joint (%s) not found", name.c_str());
00191     }
00192     return cit->second->getJointStatus();
00193 }
00194 
00195 void RobotController::update()
00196 {
00197     common::Time currTime = modelPtr->GetWorld()->GetSimTime();
00198     common::Time stepTime = currTime - prevUpdateTime;
00199     prevUpdateTime = currTime;
00200 
00201     for (std::map<std::string, JointControllerPtr>::iterator it = joints.begin(); it != joints.end(); ++it)
00202     {
00203         it->second->update(stepTime);
00204     }
00205 }
00206 
00207 void RobotController::publishJointStatuses(ros::Publisher& rosPub) const
00208 {
00209     r2_msgs::JointStatusArray statusArray;
00210     statusArray.header.stamp = ros::Time::now();
00211     for (std::map<std::string, JointControllerPtr>::const_iterator it = joints.begin(); it != joints.end(); ++it)
00212     {
00213         statusArray.status.push_back(it->second->getJointStatus());
00214     }
00215     rosPub.publish(statusArray);
00216 }