$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 #include <pr2_gazebo_plugins/gazebo_ros_controller_manager.h> 00031 #include <fstream> 00032 #include <iostream> 00033 #include <math.h> 00034 #include <unistd.h> 00035 #include <set> 00036 #include <gazebo/Global.hh> 00037 #include <gazebo/World.hh> 00038 #include <gazebo/PhysicsEngine.hh> 00039 #include <gazebo/XMLConfig.hh> 00040 #include <gazebo/Model.hh> 00041 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00042 #include <gazebo/Joint.hh> 00043 #else 00044 #include <gazebo/HingeJoint.hh> 00045 #include <gazebo/SliderJoint.hh> 00046 #endif 00047 #include <gazebo/Simulator.hh> 00048 #include <gazebo/gazebo.h> 00049 #include <angles/angles.h> 00050 #include <gazebo/GazeboError.hh> 00051 #include <gazebo/ControllerFactory.hh> 00052 #include <urdf/model.h> 00053 #include <map> 00054 00055 namespace gazebo { 00056 00057 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_controller_manager", GazeboRosControllerManager); 00058 00059 GazeboRosControllerManager::GazeboRosControllerManager(Entity *parent) 00060 : Controller(parent), hw_(), fake_calibration_(true) 00061 { 00062 this->parent_model_ = dynamic_cast<Model*>(this->parent); 00063 00064 if (!this->parent_model_) 00065 gzthrow("GazeboRosControllerManager controller requires a Model as its parent"); 00066 00067 Param::Begin(&this->parameters); 00068 this->robotParamP = new ParamT<std::string>("robotParam", "robot_description", 0); 00069 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00070 this->setModelsJointsStatesServiceNameP = new ParamT<std::string>("setModelsJointsStatesServiceName","set_models_joints_states", 0); 00071 Param::End(); 00072 00073 if (getenv("CHECK_SPEEDUP")) 00074 { 00075 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00076 wall_start_ = Simulator::Instance()->GetRealTime().Double(); 00077 sim_start_ = Simulator::Instance()->GetSimTime().Double(); 00078 #else 00079 wall_start_ = Simulator::Instance()->GetRealTime(); 00080 sim_start_ = Simulator::Instance()->GetSimTime(); 00081 #endif 00082 } 00083 00084 // check update rate against world physics update rate 00085 // should be equal or higher to guarantee the wrench applied is not "diluted" 00086 if (this->updatePeriod > 0 && 00087 (gazebo::World::Instance()->GetPhysicsEngine()->GetUpdateRate() > 1.0/this->updatePeriod)) 00088 ROS_ERROR("gazebo_ros_force controller update rate is less than physics update rate, wrench applied will be diluted (applied intermittently)"); 00089 00090 00091 } 00092 00094 bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req, 00095 pr2_gazebo_plugins::SetModelsJointsStates::Response &res) 00096 { 00097 00098 return true; 00099 } 00100 00101 00102 GazeboRosControllerManager::~GazeboRosControllerManager() 00103 { 00104 delete this->robotParamP; 00105 delete this->robotNamespaceP; 00106 delete this->cm_; 00107 delete this->rosnode_; 00108 00109 if (this->fake_state_) 00110 { 00111 // why does this cause double free corrpution in destruction of RobotState? 00112 //this->fake_state_->~RobotState(); 00113 delete this->fake_state_; 00114 } 00115 } 00116 00117 void GazeboRosControllerManager::LoadChild(XMLConfigNode *node) 00118 { 00119 // get parameter name 00120 this->robotParamP->Load(node); 00121 this->robotParam = this->robotParamP->GetValue(); 00122 this->robotNamespaceP->Load(node); 00123 this->robotNamespace = this->robotNamespaceP->GetValue(); 00124 00125 if (!ros::isInitialized()) 00126 { 00127 int argc = 0; 00128 char** argv = NULL; 00129 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00130 } 00131 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00132 ROS_INFO("starting gazebo_ros_controller_manager plugin in ns: %s",this->robotNamespace.c_str()); 00133 00134 this->cm_ = new pr2_controller_manager::ControllerManager(&hw_,*this->rosnode_); 00135 00136 this->rosnode_->param("gazebo/start_robot_calibrated",this->fake_calibration_,true); 00137 00138 // read pr2 urdf 00139 // setup actuators, then setup mechanism control node 00140 ReadPr2Xml(node); 00141 00142 // Initializes the fake state (for running the transmissions backwards). 00143 this->fake_state_ = new pr2_mechanism_model::RobotState(&this->cm_->model_); 00144 00145 // The gazebo joints and mechanism joints should match up. 00146 if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful 00147 { 00148 for (unsigned int i = 0; i < this->cm_->state_->joint_states_.size(); ++i) 00149 { 00150 std::string joint_name = this->cm_->state_->joint_states_[i].joint_->name; 00151 00152 // fill in gazebo joints pointer 00153 gazebo::Joint *joint = this->parent_model_->GetJoint(joint_name); 00154 if (joint) 00155 { 00156 this->joints_.push_back(joint); 00157 } 00158 else 00159 { 00160 //ROS_WARN("A joint named \"%s\" is not part of Mechanism Controlled joints.\n", joint_name.c_str()); 00161 this->joints_.push_back(NULL); 00162 } 00163 00164 } 00165 } 00166 00167 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00168 this->hw_.current_time_ = ros::Time(Simulator::Instance()->GetSimTime().Double()); 00169 #else 00170 this->hw_.current_time_ = ros::Time(Simulator::Instance()->GetSimTime()); 00171 #endif 00172 } 00173 00174 void GazeboRosControllerManager::InitChild() 00175 { 00176 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00177 this->hw_.current_time_ = ros::Time(Simulator::Instance()->GetSimTime().Double()); 00178 #else 00179 this->hw_.current_time_ = ros::Time(Simulator::Instance()->GetSimTime()); 00180 #endif 00181 #ifdef USE_CBQ 00182 // start custom queue for controller manager 00183 this->controller_manager_callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerQueueThread,this ) ); 00184 #endif 00185 00186 // pr2_etherCAT calls ros::spin(), we'll thread out one spinner here to mimic that 00187 this->ros_spinner_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerROSThread,this ) ); 00188 00189 } 00190 00191 void GazeboRosControllerManager::UpdateChild() 00192 { 00193 if (gazebo::Simulator::Instance()->IsPaused()) return; 00194 00195 if (getenv("CHECK_SPEEDUP")) 00196 { 00197 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00198 double wall_elapsed = Simulator::Instance()->GetRealTime().Double() - wall_start_; 00199 double sim_elapsed = Simulator::Instance()->GetSimTime().Double() - sim_start_; 00200 #else 00201 double wall_elapsed = Simulator::Instance()->GetRealTime() - wall_start_; 00202 double sim_elapsed = Simulator::Instance()->GetSimTime() - sim_start_; 00203 #endif 00204 std::cout << " real time: " << wall_elapsed 00205 << " sim time: " << sim_elapsed 00206 << " speed up: " << sim_elapsed / wall_elapsed 00207 << std::endl; 00208 } 00209 assert(this->joints_.size() == this->fake_state_->joint_states_.size()); 00210 00211 //-------------------------------------------------- 00212 // Pushes out simulation state 00213 //-------------------------------------------------- 00214 00215 // Copies the state from the gazebo joints into the mechanism joints. 00216 for (unsigned int i = 0; i < this->joints_.size(); ++i) 00217 { 00218 if (!this->joints_[i]) 00219 continue; 00220 00221 double damping_coef; 00222 if (this->cm_->state_->joint_states_[i].joint_->dynamics) 00223 damping_coef = this->cm_->state_->joint_states_[i].joint_->dynamics->damping; 00224 else 00225 damping_coef = 0; 00226 00227 this->fake_state_->joint_states_[i].measured_effort_ = this->fake_state_->joint_states_[i].commanded_effort_; 00228 00229 switch(this->joints_[i]->GetType()) 00230 { 00231 case Joint::HINGE: { 00232 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00233 Joint *hj = this->joints_[i]; 00234 this->fake_state_->joint_states_[i].position_ = this->fake_state_->joint_states_[i].position_ + 00235 angles::shortest_angular_distance(this->fake_state_->joint_states_[i].position_,hj->GetAngle(0).GetAsRadian()); 00236 this->fake_state_->joint_states_[i].velocity_ = hj->GetVelocity(0); 00237 #else 00238 HingeJoint *hj = (HingeJoint*)this->joints_[i]; 00239 this->fake_state_->joint_states_[i].position_ = this->fake_state_->joint_states_[i].position_ + 00240 angles::shortest_angular_distance(this->fake_state_->joint_states_[i].position_,hj->GetAngle()); 00241 this->fake_state_->joint_states_[i].velocity_ = hj->GetAngleRate(); 00242 #endif 00243 break; 00244 } 00245 case Joint::SLIDER: { 00246 #ifndef ODE_SCREW_JOINT 00247 static double torso_hack_damping_threshold = 1000.0; 00248 #endif 00249 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00250 Joint *sj = this->joints_[i]; 00251 #ifndef ODE_SCREW_JOINT 00252 if (damping_coef > torso_hack_damping_threshold) 00253 { 00254 this->fake_state_->joint_states_[i].position_ *= (1.0 - torso_hack_damping_threshold / damping_coef); 00255 this->fake_state_->joint_states_[i].position_ += (torso_hack_damping_threshold/damping_coef)*sj->GetAngle(0).GetAsRadian(); 00256 this->fake_state_->joint_states_[i].velocity_ *= (1.0 - torso_hack_damping_threshold / damping_coef); 00257 this->fake_state_->joint_states_[i].velocity_ += (torso_hack_damping_threshold/damping_coef)*sj->GetVelocity(0); 00258 } 00259 else 00260 #endif 00261 { 00262 this->fake_state_->joint_states_[i].position_ = sj->GetAngle(0).GetAsRadian(); 00263 this->fake_state_->joint_states_[i].velocity_ = sj->GetVelocity(0); 00264 } 00265 break; 00266 #else 00267 SliderJoint *sj = (SliderJoint*)this->joints_[i]; 00268 #ifndef ODE_SCREW_JOINT 00269 if (damping_coef > torso_hack_damping_threshold) 00270 { 00271 this->fake_state_->joint_states_[i].position_ *= (1.0 - torso_hack_damping_threshold / damping_coef); 00272 this->fake_state_->joint_states_[i].position_ += (torso_hack_damping_threshold/damping_coef)*sj->GetPosition(); 00273 this->fake_state_->joint_states_[i].velocity_ *= (1.0 - torso_hack_damping_threshold / damping_coef); 00274 this->fake_state_->joint_states_[i].velocity_ += (torso_hack_damping_threshold/damping_coef)*sj->GetPositionRate(); 00275 } 00276 else 00277 #endif 00278 { 00279 this->fake_state_->joint_states_[i].position_ = sj->GetPosition(); 00280 this->fake_state_->joint_states_[i].velocity_ = sj->GetPositionRate(); 00281 } 00282 break; 00283 #endif 00284 } 00285 default: 00286 abort(); 00287 } 00288 } 00289 00290 // Reverses the transmissions to propagate the joint position into the actuators. 00291 this->fake_state_->propagateJointPositionToActuatorPosition(); 00292 00293 //-------------------------------------------------- 00294 // Runs Mechanism Control 00295 //-------------------------------------------------- 00296 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00297 this->hw_.current_time_ = ros::Time(Simulator::Instance()->GetSimTime().Double()); 00298 #else 00299 this->hw_.current_time_ = ros::Time(Simulator::Instance()->GetSimTime()); 00300 #endif 00301 try 00302 { 00303 if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful 00304 this->cm_->update(); 00305 } 00306 catch (const char* c) 00307 { 00308 if (strcmp(c,"dividebyzero")==0) 00309 ROS_WARN("pid controller reports divide by zero error"); 00310 else 00311 ROS_WARN("unknown const char* exception: %s", c); 00312 } 00313 00314 //-------------------------------------------------- 00315 // Takes in actuation commands 00316 //-------------------------------------------------- 00317 00318 // Reverses the transmissions to propagate the actuator commands into the joints. 00319 this->fake_state_->propagateActuatorEffortToJointEffort(); 00320 00321 // Copies the commands from the mechanism joints into the gazebo joints. 00322 for (unsigned int i = 0; i < this->joints_.size(); ++i) 00323 { 00324 if (!this->joints_[i]) 00325 continue; 00326 00327 double effort = this->fake_state_->joint_states_[i].commanded_effort_; 00328 00329 double damping_coef; 00330 if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful 00331 { 00332 if (this->cm_->state_->joint_states_[i].joint_->dynamics) 00333 damping_coef = this->cm_->state_->joint_states_[i].joint_->dynamics->damping; 00334 else 00335 damping_coef = 0; 00336 } 00337 00338 switch (this->joints_[i]->GetType()) 00339 { 00340 case Joint::HINGE: { 00341 #if GAZEBO_MAJOR_VERSION >= 0 && GAZEBO_MINOR_VERSION >= 10 00342 Joint *hj = this->joints_[i]; 00343 #if GAZEBO_PATCH_VERSION >= 1 00344 // skip explicit damping force addition, taken care of in gazebo 00345 double effort_command = effort; 00346 #else 00347 double current_velocity = hj->GetVelocity(0); 00348 double damping_force = damping_coef * current_velocity; 00349 double effort_command = effort - damping_force; 00350 #endif 00351 hj->SetForce(0,effort_command); 00352 #else 00353 HingeJoint *hj = (HingeJoint*)this->joints_[i]; 00354 #if GAZEBO_PATCH_VERSION >= 1 00355 // skip explicit damping force addition, taken care of in gazebo 00356 double effort_command = effort; 00357 #else 00358 double current_velocity = hj->GetAngleRate(); 00359 double damping_force = damping_coef * current_velocity; 00360 double effort_command = effort - damping_force; 00361 #endif 00362 hj->SetTorque(effort_command); 00363 #endif 00364 break; 00365 } 00366 case Joint::SLIDER: { 00367 #if GAZEBO_MAJOR_VERSION == 0 && GAZEBO_MINOR_VERSION >= 10 00368 Joint *sj = this->joints_[i]; 00369 #if GAZEBO_PATCH_VERSION >= 1 00370 double effort_command = effort; 00371 #else 00372 double current_velocity = sj->GetVelocity(0); 00373 double damping_force = damping_coef * current_velocity; 00374 double effort_command = effort-damping_force; 00375 #endif 00376 (this->joints_[i])->SetForce(0,effort_command); 00377 #else 00378 SliderJoint *sj = (SliderJoint*)this->joints_[i]; 00379 #if GAZEBO_PATCH_VERSION >= 1 00380 double effort_command = effort; 00381 #else 00382 double current_velocity = sj->GetPositionRate(); 00383 double damping_force = damping_coef * current_velocity; 00384 double effort_command = effort-damping_force; 00385 #endif 00386 sj->SetSliderForce(effort_command); 00387 #endif 00388 break; 00389 } 00390 default: 00391 abort(); 00392 } 00393 } 00394 } 00395 00396 void GazeboRosControllerManager::FiniChild() 00397 { 00398 ROS_DEBUG("Calling FiniChild in GazeboRosControllerManager"); 00399 00400 //pr2_hardware_interface::ActuatorMap::const_iterator it; 00401 //for (it = hw_.actuators_.begin(); it != hw_.actuators_.end(); ++it) 00402 // delete it->second; // why is this causing double free corrpution? 00403 this->cm_->~ControllerManager(); 00404 this->rosnode_->shutdown(); 00405 #ifdef USE_CBQ 00406 this->controller_manager_queue_.clear(); 00407 this->controller_manager_queue_.disable(); 00408 this->controller_manager_callback_queue_thread_.join(); 00409 #endif 00410 this->ros_spinner_thread_.join(); 00411 } 00412 00413 void GazeboRosControllerManager::ReadPr2Xml(XMLConfigNode *node) 00414 { 00415 00416 std::string urdf_param_name; 00417 std::string urdf_string; 00418 // search and wait for robot_description on param server 00419 while(urdf_string.empty()) 00420 { 00421 ROS_DEBUG("gazebo controller manager plugin is waiting for urdf: %s on the param server.", this->robotParam.c_str()); 00422 if (this->rosnode_->searchParam(this->robotParam,urdf_param_name)) 00423 { 00424 this->rosnode_->getParam(urdf_param_name,urdf_string); 00425 ROS_DEBUG("found upstream\n%s\n------\n%s\n------\n%s",this->robotParam.c_str(),urdf_param_name.c_str(),urdf_string.c_str()); 00426 } 00427 else 00428 { 00429 this->rosnode_->getParam(this->robotParam,urdf_string); 00430 ROS_DEBUG("found in node namespace\n%s\n------\n%s\n------\n%s",this->robotParam.c_str(),urdf_param_name.c_str(),urdf_string.c_str()); 00431 } 00432 usleep(100000); 00433 } 00434 ROS_DEBUG("gazebo controller manager got pr2.xml from param server, parsing it..."); 00435 00436 // initialize TiXmlDocument doc with a string 00437 TiXmlDocument doc; 00438 if (!doc.Parse(urdf_string.c_str()) && doc.Error()) 00439 { 00440 ROS_ERROR("Could not load the gazebo controller manager plugin's configuration file: %s\n", 00441 urdf_string.c_str()); 00442 } 00443 else 00444 { 00445 //doc.Print(); 00446 //std::cout << *(doc.RootElement()) << std::endl; 00447 00448 // Pulls out the list of actuators used in the robot configuration. 00449 struct GetActuators : public TiXmlVisitor 00450 { 00451 std::set<std::string> actuators; 00452 virtual bool VisitEnter(const TiXmlElement &elt, const TiXmlAttribute *) 00453 { 00454 if (elt.ValueStr() == std::string("actuator") && elt.Attribute("name")) 00455 actuators.insert(elt.Attribute("name")); 00456 else if (elt.ValueStr() == std::string("rightActuator") && elt.Attribute("name")) 00457 actuators.insert(elt.Attribute("name")); 00458 else if (elt.ValueStr() == std::string("leftActuator") && elt.Attribute("name")) 00459 actuators.insert(elt.Attribute("name")); 00460 return true; 00461 } 00462 } get_actuators; 00463 doc.RootElement()->Accept(&get_actuators); 00464 00465 // Places the found actuators into the hardware interface. 00466 std::set<std::string>::iterator it; 00467 for (it = get_actuators.actuators.begin(); it != get_actuators.actuators.end(); ++it) 00468 { 00469 //std::cout << " adding actuator " << (*it) << std::endl; 00470 pr2_hardware_interface::Actuator* pr2_actuator = new pr2_hardware_interface::Actuator(*it); 00471 pr2_actuator->state_.is_enabled_ = true; 00472 this->hw_.addActuator(pr2_actuator); 00473 } 00474 00475 // Setup mechanism control node 00476 this->cm_->initXml(doc.RootElement()); 00477 00478 for (unsigned int i = 0; i < this->cm_->state_->joint_states_.size(); ++i) 00479 this->cm_->state_->joint_states_[i].calibrated_ = fake_calibration_; 00480 } 00481 } 00482 00483 #ifdef USE_CBQ 00484 00485 // custom callback queue 00486 void GazeboRosControllerManager::ControllerManagerQueueThread() 00487 { 00488 ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id()); 00489 00490 static const double timeout = 0.01; 00491 00492 while (this->rosnode_->ok()) 00493 { 00494 this->controller_manager_queue_.callAvailable(ros::WallDuration(timeout)); 00495 } 00496 } 00497 #endif 00498 00499 void GazeboRosControllerManager::ControllerManagerROSThread() 00500 { 00501 ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id()); 00502 00503 //ros::Rate rate(1000); 00504 00505 while (this->rosnode_->ok()) 00506 { 00507 //rate.sleep(); // using rosrate gets stuck on model delete 00508 usleep(1000); 00509 ros::spinOnce(); 00510 } 00511 } 00512 } // namespace gazebo