$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 00031 #include <math.h> 00032 #include <unistd.h> 00033 #include <set> 00034 00035 #include <boost/thread.hpp> 00036 00037 #include "pr2_hardware_interface/hardware_interface.h" 00038 #include "pr2_controller_manager/controller_manager.h" 00039 #include "pr2_mechanism_model/robot.h" 00040 #include "tinyxml/tinyxml.h" 00041 00042 #include <XmlRpcValue.h> 00043 #include <XmlRpcException.h> 00044 00045 #include <ros/ros.h> 00046 00047 #include <urdf/model.h> 00048 00049 class LoopbackControllerManager 00050 { 00051 public: 00052 LoopbackControllerManager(); 00053 virtual ~LoopbackControllerManager(); 00054 00055 // Inherited from gazebo::Controller 00056 void init(); 00057 void update(); 00058 void fini(); 00059 00060 void run(); 00061 private: 00062 00063 pr2_hardware_interface::HardwareInterface hw_; 00064 pr2_controller_manager::ControllerManager *cm_; 00065 00066 pr2_mechanism_model::RobotState *state_; 00067 00068 void readUrdf(); 00069 00070 ros::NodeHandle* rosnode_; 00071 ros::Subscriber desired_angles_sub_; 00072 00073 void ControllerManagerROSThread(); 00074 void jointCallback(const sensor_msgs::JointState::ConstPtr &joints); 00075 boost::thread* ros_spinner_thread_; 00076 boost::mutex lock; 00077 00078 double dt_; 00079 double damping_; 00080 double mass_; 00081 00082 void simulateJoints(); 00083 }; 00084 00085 00086 using namespace std; 00087 using namespace XmlRpc; 00088 00089 00090 LoopbackControllerManager::LoopbackControllerManager() 00091 : hw_(), state_(NULL), dt_(0.0) 00092 { 00093 } 00094 00095 00096 LoopbackControllerManager::~LoopbackControllerManager() 00097 { 00098 delete cm_; 00099 delete rosnode_; 00100 delete ros_spinner_thread_; 00101 } 00102 00103 void LoopbackControllerManager::jointCallback(const sensor_msgs::JointState::ConstPtr &joints) 00104 { 00105 boost::mutex::scoped_lock mutex(lock); 00106 00107 if(joints->name.size() != joints->position.size()) 00108 { 00109 ROS_ERROR("received invalid desired joints."); 00110 return; 00111 } 00112 00113 for(unsigned int i=0; i < joints->name.size(); ++i) 00114 { 00115 state_->getJointState(joints->name[i])->position_ = joints->position[i]; 00116 } 00117 00118 } 00119 00120 void LoopbackControllerManager::init() 00121 { 00122 rosnode_ = new ros::NodeHandle("/"); 00123 cm_ = new pr2_controller_manager::ControllerManager(&hw_,*rosnode_); 00124 readUrdf(); // read urdf, setup actuators, then setup mechanism control node 00125 00126 ros::NodeHandle private_node = ros::NodeHandle("~"); 00127 private_node.param("dt", dt_, 0.01); 00128 private_node.param("damping", damping_, 0.1); 00129 private_node.param("mass", mass_, 0.1); 00130 00131 desired_angles_sub_ = private_node.subscribe("desired_joints", 1, &LoopbackControllerManager::jointCallback, this); 00132 00133 state_ = cm_->state_; 00134 00135 // set all joints to zero 00136 for(unsigned int i = 0; i < state_->joint_states_.size(); i++) 00137 { 00138 pr2_mechanism_model::JointState &s = state_->joint_states_[i]; 00139 s.position_ = 0.0; 00140 s.velocity_ = 0.0; 00141 s.measured_effort_ = 0.0; 00142 s.commanded_effort_ = 0.0; 00143 } 00144 00145 // set some joints to different starting positions 00146 try 00147 { 00148 XmlRpcValue jointLists, nameList, valueList; 00149 if(private_node.getParam("joints", jointLists)) 00150 { 00151 nameList = jointLists["name"]; 00152 valueList = jointLists["position"]; 00153 for (int index = 0; index < nameList.size(); index++) 00154 { 00155 pr2_mechanism_model::JointState *s = 00156 state_->getJointState((string) nameList[index]); 00157 if(s) 00158 s->position_ = (double) valueList[index]; 00159 } 00160 } 00161 } 00162 catch(XmlRpcException e) 00163 { 00164 // syntax error, print the (pretty useless) error message 00165 ROS_WARN("Error parsing initial joint positions: %s", e.getMessage().c_str()); 00166 } 00167 00168 00169 // adjust joint positions to not violate soft limits 00170 for(unsigned int i = 0; i < state_->joint_states_.size(); i++) 00171 { 00172 pr2_mechanism_model::JointState &s = state_->joint_states_[i]; 00173 const boost::shared_ptr<urdf::JointSafety> safety = s.joint_->safety; 00174 00175 if(safety) 00176 { 00177 double lower = safety->soft_lower_limit; 00178 double upper = safety->soft_upper_limit; 00179 if(lower != 0.0 || upper != 0.0) 00180 { 00181 double margin = (upper - lower) * 0.001; 00182 lower += margin; 00183 upper -= margin; 00184 double pos_old = s.position_; 00185 00186 s.position_ = (s.position_ < lower) ? lower : s.position_; 00187 s.position_ = (s.position_ > upper) ? upper : s.position_; 00188 00189 if(s.position_ != pos_old) 00190 ROS_INFO("adjusted joint %s to %f", s.joint_->name.c_str(), s.position_); 00191 } 00192 } 00193 } 00194 00195 hw_.current_time_ = ros::Time::now(); 00196 00197 // pr2_etherCAT calls ros::spin(), we'll thread out one spinner here to mimic that 00198 ros_spinner_thread_ = new boost::thread( boost::bind( &LoopbackControllerManager::ControllerManagerROSThread,this ) ); 00199 00200 } 00201 00202 00203 void LoopbackControllerManager::simulateJoints() 00204 { 00205 // \todo: We should use KDL to do correct dynamics 00206 00207 for (unsigned int i = 0; i < state_->joint_states_.size(); ++i) 00208 { 00209 pr2_mechanism_model::JointState &s = state_->joint_states_[i]; 00210 const boost::shared_ptr<urdf::JointDynamics> dynamics = state_->joint_states_[i].joint_->dynamics; 00211 00212 // use damping from urdf (if specified) 00213 double damp = (dynamics) ? dynamics->damping : damping_; 00214 double effort = s.commanded_effort_ - damp*s.velocity_; 00215 00216 double dv = effort/mass_*dt_; 00217 s.velocity_ += dv; 00218 00219 double dx = s.velocity_*dt_; 00220 s.position_ += dx; 00221 } 00222 } 00223 00224 00225 void LoopbackControllerManager::update() 00226 { 00227 boost::mutex::scoped_lock mutex(lock); 00228 00229 // Copies the state from the gazebo joints into the mechanism joints. 00230 for (unsigned int i = 0; i < state_->joint_states_.size(); ++i) 00231 { 00232 state_->joint_states_[i].measured_effort_ = state_->joint_states_[i].commanded_effort_; 00233 } 00234 00235 // Reverses the transmissions to propagate the joint position into the actuators. 00236 state_->propagateJointPositionToActuatorPosition(); 00237 00238 //-------------------------------------------------- 00239 // Runs Mechanism Control 00240 //-------------------------------------------------- 00241 00242 // \todo: necessary? 00243 hw_.current_time_ = ros::Time::now(); 00244 00245 try 00246 { 00247 cm_->update(); 00248 } 00249 catch (const char* c) 00250 { 00251 if (strcmp(c,"dividebyzero")==0) 00252 ROS_WARN("pid controller reports divide by zero error"); 00253 else 00254 ROS_WARN("unknown const char* exception: %s", c); 00255 } 00256 00257 //-------------------------------------------------- 00258 // Simulate the effort commands 00259 //-------------------------------------------------- 00260 00261 // Reverses the transmissions to propagate the actuator commands into the joints. 00262 state_->propagateActuatorEffortToJointEffort(); 00263 00264 simulateJoints(); 00265 } 00266 00267 void LoopbackControllerManager::fini() 00268 { 00269 ROS_DEBUG("calling LoopbackControllerManager::fini"); 00270 00271 //pr2_hardware_interface::ActuatorMap::const_iterator it; 00272 //for (it = hw_.actuators_.begin(); it != hw_.actuators_.end(); ++it) 00273 // delete it->second; // why is this causing double free corrpution? 00274 cm_->~ControllerManager(); 00275 rosnode_->shutdown(); 00276 00277 ros_spinner_thread_->join(); 00278 } 00279 00280 void LoopbackControllerManager::readUrdf() 00281 { 00282 std::string urdf_string; 00283 rosnode_->getParam("/robot_description", urdf_string); 00284 00285 // initialize TiXmlDocument doc with a string 00286 TiXmlDocument doc; 00287 if (!doc.Parse(urdf_string.c_str())) 00288 { 00289 ROS_ERROR("Failed to load robot description"); 00290 abort(); 00291 } 00292 00293 struct GetActuators : public TiXmlVisitor 00294 { 00295 std::set<std::string> actuators; 00296 virtual bool VisitEnter(const TiXmlElement &elt, const TiXmlAttribute *) 00297 { 00298 if (elt.Attribute("name") && 00299 ( elt.ValueStr() == std::string("actuator") 00300 || elt.ValueStr() == std::string("rightActuator") 00301 || elt.ValueStr() == std::string("leftActuator") )) 00302 actuators.insert(elt.Attribute("name")); 00303 return true; 00304 } 00305 } get_actuators; 00306 doc.RootElement()->Accept(&get_actuators); 00307 00308 // Places the found actuators into the hardware interface. 00309 std::set<std::string>::iterator it; 00310 for (it = get_actuators.actuators.begin(); it != get_actuators.actuators.end(); ++it) 00311 { 00312 // ROS_INFO_STREAM("adding actuator " << *it); 00313 pr2_hardware_interface::Actuator* pr2_actuator = new pr2_hardware_interface::Actuator(*it); 00314 pr2_actuator->state_.is_enabled_ = true; 00315 hw_.addActuator(pr2_actuator); 00316 } 00317 00318 // Setup mechanism control node 00319 cm_->initXml(doc.RootElement()); 00320 00321 for (unsigned int i = 0; i < cm_->state_->joint_states_.size(); ++i) 00322 cm_->state_->joint_states_[i].calibrated_ = true; 00323 } 00324 00325 00326 void LoopbackControllerManager::ControllerManagerROSThread() 00327 { 00328 ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id()); 00329 00330 ros::Rate rate(0.2/dt_); 00331 00332 while (rosnode_->ok()) 00333 { 00334 rate.sleep(); 00335 ros::spinOnce(); 00336 } 00337 } 00338 00339 00340 void LoopbackControllerManager::run() 00341 { 00342 00343 ros::Rate rate(1.0/dt_); 00344 while(rosnode_->ok()) 00345 { 00346 update(); 00347 rate.sleep(); 00348 } 00349 } 00350 00351 00352 int main(int argc, char *argv[]) 00353 { 00354 ros::init(argc,argv,"loopback_controllers"); 00355 00356 // bring up mechanism controllers 00357 LoopbackControllerManager m; 00358 00359 m.init(); 00360 m.run(); 00361 m.fini(); 00362 }