gazebo_ros_controller_manager.cpp
Go to the documentation of this file.
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 <sr_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 
00037 //#include <gazebo/XMLConfig.hh>
00038 //#include "physics/physics.h"
00039 #include "physics/World.hh"
00040 #include "physics/HingeJoint.hh"
00041 #include "sensors/Sensor.hh"
00042 #include "sdf/interface/SDF.hh"
00043 #include "sdf/interface/Param.hh"
00044 #include "common/Exception.hh"
00045 #include "physics/PhysicsTypes.hh"
00046 #include "physics/Base.hh"
00047 
00048 
00049 #include <angles/angles.h>
00050 #include <urdf/model.h>
00051 #include <map>
00052 
00053 #include <sr_hardware_interface/sr_actuator.hpp>
00054 
00055 namespace gazebo {
00056 
00057 GazeboRosControllerManager::GazeboRosControllerManager()
00058 {
00059 }
00060 
00061 
00063 bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req,
00064                            pr2_gazebo_plugins::SetModelsJointsStates::Response &res)
00065 {
00066 
00067   return true;
00068 }
00069 
00070 
00071 GazeboRosControllerManager::~GazeboRosControllerManager()
00072 {
00073   ROS_DEBUG("Calling FiniChild in GazeboRosControllerManager");
00074 
00075   //pr2_hardware_interface::ActuatorMap::const_iterator it;
00076   //for (it = hw_.actuators_.begin(); it != hw_.actuators_.end(); ++it)
00077   //  delete it->second; // why is this causing double free corrpution?
00078   this->cm_->~ControllerManager();
00079   this->rosnode_->shutdown();
00080 #ifdef USE_CBQ
00081   this->controller_manager_queue_.clear();
00082   this->controller_manager_queue_.disable();
00083   this->controller_manager_callback_queue_thread_.join();
00084 #endif
00085   this->ros_spinner_thread_.join();
00086 
00087 
00088 
00089 
00090   delete this->cm_;
00091   delete this->rosnode_;
00092 
00093   if (this->fake_state_)
00094   {
00095     // why does this cause double free corrpution in destruction of RobotState?
00096     //this->fake_state_->~RobotState();
00097     delete this->fake_state_;
00098   }
00099 }
00100 
00101 
00102 void GazeboRosControllerManager::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00103 {
00104   // Get then name of the parent model
00105   std::string modelName = _sdf->GetParent()->GetValueString("name");
00106 
00107   // Get the world name.
00108   this->world = _parent->GetWorld();
00109 
00110   // Get a pointer to the model
00111   this->parent_model_ = _parent;
00112 
00113   // Error message if the model couldn't be found
00114   if (!this->parent_model_)
00115     gzerr << "Unable to get parent model\n";
00116 
00117   // Listen to the update event. This event is broadcast every
00118   // simulation iteration.
00119   this->updateConnection = event::Events::ConnectWorldUpdateStart(
00120       boost::bind(&GazeboRosControllerManager::UpdateChild, this));
00121   gzdbg << "plugin model name: " << modelName << "\n";
00122 
00123 
00124 
00125 
00126   if (getenv("CHECK_SPEEDUP"))
00127   {
00128     wall_start_ = this->world->GetRealTime().Double();
00129     sim_start_  = this->world->GetSimTime().Double();
00130   }
00131 
00132   // check update rate against world physics update rate
00133   // should be equal or higher to guarantee the wrench applied is not "diluted"
00134   //if (this->updatePeriod > 0 &&
00135   //    (this->world->GetPhysicsEngine()->GetUpdateRate() > 1.0/this->updatePeriod))
00136   //  ROS_ERROR("gazebo_ros_force controller update rate is less than physics update rate, wrench applied will be diluted (applied intermittently)");
00137 
00138 
00139 
00140 
00141 
00142   // get parameter name
00143   this->robotNamespace = "";
00144   if (_sdf->HasElement("robotNamespace"))
00145     this->robotNamespace = _sdf->GetElement("robotNamespace")->GetValueString();
00146 
00147   this->robotParam = "robot_description";
00148   if (_sdf->HasElement("robotParam"))
00149     this->robotParam = _sdf->GetElement("robotParam")->GetValueString();
00150 
00151   this->robotParam = this->robotNamespace+"/" + this->robotParam;
00152 
00153   if (!ros::isInitialized())
00154   {
00155     int argc = 0;
00156     char** argv = NULL;
00157     ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00158   }
00159   this->rosnode_ = new ros::NodeHandle(this->robotNamespace);
00160   ROS_INFO("starting gazebo_ros_controller_manager plugin in ns: %s",this->robotNamespace.c_str());
00161 
00162   // pr2_etherCAT calls ros::spin(), we'll thread out one spinner here to mimic that
00163   this->ros_spinner_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerROSThread,this ) );
00164 
00165 
00166   // load a controller manager
00167   this->cm_ = new pr2_controller_manager::ControllerManager(&hw_,*this->rosnode_);
00168   this->hw_.current_time_ = ros::Time(this->world->GetSimTime().Double());
00169   if (this->hw_.current_time_ < ros::Time(0.001)) this->hw_.current_time_ == ros::Time(0.001); // hardcoded to minimum of 1ms on start up
00170 
00171   this->rosnode_->param("gazebo/start_robot_calibrated",this->fake_calibration_,true);
00172 
00173   // read pr2 urdf
00174   // setup actuators, then setup mechanism control node
00175   ReadPr2Xml();
00176 
00177   // Initializes the fake state (for running the transmissions backwards).
00178   this->fake_state_ = new pr2_mechanism_model::RobotState(&this->cm_->model_);
00179 
00180   // The gazebo joints and mechanism joints should match up.
00181   if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful
00182   {
00183     for (unsigned int i = 0; i < this->cm_->state_->joint_states_.size(); ++i)
00184     {
00185       std::string joint_name = this->cm_->state_->joint_states_[i].joint_->name;
00186 
00187       // fill in gazebo joints pointer
00188       gazebo::physics::JointPtr joint = this->parent_model_->GetJoint(joint_name);
00189       if (joint)
00190       {
00191         this->joints_.push_back(joint);
00192       }
00193       else
00194       {
00195         //ROS_WARN("A joint named \"%s\" is not part of Mechanism Controlled joints.\n", joint_name.c_str());
00196         //this->joints_.push_back(NULL);  // FIXME: cannot be null, must be an empty boost shared pointer
00197         this->joints_.push_back(gazebo::physics::JointPtr());  // FIXME: cannot be null, must be an empty boost shared pointer
00198         ROS_ERROR("A joint named \"%s\" is not part of Mechanism Controlled joints.\n", joint_name.c_str());
00199       }
00200 
00201     }
00202   }
00203 
00204 #ifdef USE_CBQ
00205   // start custom queue for controller manager
00206   this->controller_manager_callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerQueueThread,this ) );
00207 #endif
00208 
00209 }
00210 
00211 
00212 void GazeboRosControllerManager::UpdateChild()
00213 {
00214   if (this->world->IsPaused()) return;
00215 
00216   if (getenv("CHECK_SPEEDUP"))
00217   {
00218     double wall_elapsed = this->world->GetRealTime().Double() - wall_start_;
00219     double sim_elapsed  = this->world->GetSimTime().Double()  - sim_start_;
00220     std::cout << " real time: " <<  wall_elapsed
00221               << "  sim time: " <<  sim_elapsed
00222               << "  speed up: " <<  sim_elapsed / wall_elapsed
00223               << std::endl;
00224   }
00225   assert(this->joints_.size() == this->fake_state_->joint_states_.size());
00226 
00227   //--------------------------------------------------
00228   //  Pushes out simulation state
00229   //--------------------------------------------------
00230 
00231   //ROS_ERROR("joints_.size()[%d]",(int)this->joints_.size());
00232   // Copies the state from the gazebo joints into the mechanism joints.
00233   for (unsigned int i = 0; i < this->joints_.size(); ++i)
00234   {
00235     if (!this->joints_[i])
00236       continue;
00237 
00238     this->fake_state_->joint_states_[i].measured_effort_ = this->fake_state_->joint_states_[i].commanded_effort_;
00239 
00240     if (this->joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT))
00241     {
00242       gazebo::physics::JointPtr hj = this->joints_[i];
00243       this->fake_state_->joint_states_[i].position_ = this->fake_state_->joint_states_[i].position_ +
00244                     angles::shortest_angular_distance(this->fake_state_->joint_states_[i].position_,hj->GetAngle(0).GetAsRadian());
00245       this->fake_state_->joint_states_[i].velocity_ = hj->GetVelocity(0);
00246       //if (this->joints_[i]->GetName() == "torso_lift_motor_screw_joint")
00247       //  ROS_WARN("joint[%s] [%f]",this->joints_[i]->GetName().c_str(), this->fake_state_->joint_states_[i].position_);
00248     }
00249     else if (this->joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT))
00250     {
00251       gazebo::physics::JointPtr sj = this->joints_[i];
00252       {
00253         this->fake_state_->joint_states_[i].position_ = sj->GetAngle(0).GetAsRadian();
00254         this->fake_state_->joint_states_[i].velocity_ = sj->GetVelocity(0);
00255       }
00256       //ROS_ERROR("joint[%s] is a slider [%f]",this->joints_[i]->GetName().c_str(),sj->GetAngle(0).GetAsRadian());
00257       //if (this->joints_[i]->GetName() == "torso_lift_joint")
00258       //  ROS_WARN("joint[%s] [%f]",this->joints_[i]->GetName().c_str(), this->fake_state_->joint_states_[i].position_);
00259     }
00260     else
00261     {
00262       /*
00263       ROS_WARN("joint[%s] is not hinge [%d] nor slider",this->joints_[i]->GetName().c_str(),
00264         (unsigned int)gazebo::physics::Base::HINGE_JOINT
00265         );
00266       for (unsigned int j = 0; j < this->joints_[i]->GetTypeCount(); j++)
00267       {
00268         ROS_WARN("  types: %d hinge[%d] slider[%d]",(unsigned int)this->joints_[i]->GetType(j),(unsigned int)this->joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT),(unsigned int)this->joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT));
00269       }
00270       */
00271     }
00272   }
00273 
00274   // Reverses the transmissions to propagate the joint position into the actuators.
00275   this->fake_state_->propagateJointPositionToActuatorPosition();
00276 
00277   //--------------------------------------------------
00278   //  Runs Mechanism Control
00279   //--------------------------------------------------
00280   this->hw_.current_time_ = ros::Time(this->world->GetSimTime().Double());
00281   try
00282   {
00283     if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful
00284       this->cm_->update();
00285   }
00286   catch (const char* c)
00287   {
00288     if (strcmp(c,"dividebyzero")==0)
00289       ROS_WARN("pid controller reports divide by zero error");
00290     else
00291       ROS_WARN("unknown const char* exception: %s", c);
00292   }
00293 
00294   //--------------------------------------------------
00295   //  Takes in actuation commands
00296   //--------------------------------------------------
00297 
00298   // Reverses the transmissions to propagate the actuator commands into the joints.
00299   this->fake_state_->propagateActuatorEffortToJointEffort();
00300 
00301   // Copies the commands from the mechanism joints into the gazebo joints.
00302   for (unsigned int i = 0; i < this->joints_.size(); ++i)
00303   {
00304     if (!this->joints_[i])
00305       continue;
00306 
00307     double effort = this->fake_state_->joint_states_[i].commanded_effort_;
00308 
00309     double damping_coef = 0;
00310     if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful
00311     {
00312       if (this->cm_->state_->joint_states_[i].joint_->dynamics)
00313         damping_coef = this->cm_->state_->joint_states_[i].joint_->dynamics->damping;
00314     }
00315 
00316     if (this->joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT))
00317     {
00318       gazebo::physics::JointPtr hj = this->joints_[i];
00319       double current_velocity = hj->GetVelocity(0);
00320       double damping_force = damping_coef * current_velocity;
00321       double effort_command = effort - damping_force;
00322       hj->SetForce(0,effort_command);
00323       //if (this->joints_[i]->GetName() == "torso_lift_motor_screw_joint")
00324       //  ROS_ERROR("gazebo [%s] command [%f] damping [%f]",this->joints_[i]->GetName().c_str(), effort, damping_force);
00325     }
00326     else if (this->joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT))
00327     {
00328       gazebo::physics::JointPtr sj = this->joints_[i];
00329       double current_velocity = sj->GetVelocity(0);
00330       double damping_force = damping_coef * current_velocity;
00331       double effort_command = effort-damping_force;
00332       sj->SetForce(0,effort_command);
00333       //if (this->joints_[i]->GetName() == "torso_lift_joint")
00334       //  ROS_ERROR("gazebo [%s] command [%f] damping [%f]",this->joints_[i]->GetName().c_str(), effort, damping_force);
00335     }
00336   }
00337 }
00338 
00339 void GazeboRosControllerManager::ReadPr2Xml()
00340 {
00341 
00342   std::string urdf_param_name;
00343   std::string urdf_string;
00344   // search and wait for robot_description on param server
00345   while(urdf_string.empty())
00346   {
00347     ROS_DEBUG("gazebo controller manager plugin is waiting for urdf: %s on the param server.", this->robotParam.c_str());
00348     if (this->rosnode_->searchParam(this->robotParam,urdf_param_name))
00349     {
00350       this->rosnode_->getParam(urdf_param_name,urdf_string);
00351       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());
00352     }
00353     else
00354     {
00355       this->rosnode_->getParam(this->robotParam,urdf_string);
00356       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());
00357     }
00358     usleep(100000);
00359   }
00360   ROS_DEBUG("gazebo controller manager got pr2.xml from param server, parsing it...");
00361 
00362   // initialize TiXmlDocument doc with a string
00363   TiXmlDocument doc;
00364   if (!doc.Parse(urdf_string.c_str()) && doc.Error())
00365   {
00366     ROS_ERROR("Could not load the gazebo controller manager plugin's configuration file: %s\n",
00367             urdf_string.c_str());
00368   }
00369   else
00370   {
00371     //doc.Print();
00372     //std::cout << *(doc.RootElement()) << std::endl;
00373 
00374     // Pulls out the list of actuators used in the robot configuration.
00375     struct GetActuators : public TiXmlVisitor
00376     {
00377       std::set<std::string> actuators;
00378       virtual bool VisitEnter(const TiXmlElement &elt, const TiXmlAttribute *)
00379       {
00380         if (elt.ValueStr() == std::string("actuator") && elt.Attribute("name"))
00381           actuators.insert(elt.Attribute("name"));
00382         else if (elt.ValueStr() == std::string("rightActuator") && elt.Attribute("name"))
00383           actuators.insert(elt.Attribute("name"));
00384         else if (elt.ValueStr() == std::string("leftActuator") && elt.Attribute("name"))
00385           actuators.insert(elt.Attribute("name"));
00386         return true;
00387       }
00388     } get_actuators;
00389     doc.RootElement()->Accept(&get_actuators);
00390 
00391     // Places the found actuators into the hardware interface.
00392     std::set<std::string>::iterator it;
00393     for (it = get_actuators.actuators.begin(); it != get_actuators.actuators.end(); ++it)
00394     {
00395       //std::cout << " adding actuator " << (*it) << std::endl;
00396       pr2_hardware_interface::Actuator* pr2_actuator = new sr_actuator::SrActuator(*it);
00397       pr2_actuator->state_.is_enabled_ = true;
00398       this->hw_.addActuator(pr2_actuator);
00399     }
00400 
00401     // Setup mechanism control node
00402     this->cm_->initXml(doc.RootElement());
00403 
00404     for (unsigned int i = 0; i < this->cm_->state_->joint_states_.size(); ++i)
00405       this->cm_->state_->joint_states_[i].calibrated_ = fake_calibration_;
00406   }
00407 
00408 }
00409 
00410 #ifdef USE_CBQ
00411 
00412 // custom callback queue
00413 void GazeboRosControllerManager::ControllerManagerQueueThread()
00414 {
00415   ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id());
00416 
00417   static const double timeout = 0.01;
00418 
00419   while (this->rosnode_->ok())
00420   {
00421     this->controller_manager_queue_.callAvailable(ros::WallDuration(timeout));
00422   }
00423 }
00424 #endif
00425 
00426 void GazeboRosControllerManager::ControllerManagerROSThread()
00427 {
00428   ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id());
00429 
00430   //ros::Rate rate(1000);
00431 
00432   while (this->rosnode_->ok())
00433   {
00434     //rate.sleep(); // using rosrate gets stuck on model delete
00435     usleep(1000);
00436     ros::spinOnce();
00437   }
00438 }
00439   // Register this plugin with the simulator
00440   GZ_REGISTER_MODEL_PLUGIN(GazeboRosControllerManager)
00441 } // namespace gazebo


sr_gazebo_plugins
Author(s): adapted by Ugo(software@shadowrobot.com), Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Fri Jan 3 2014 12:08:17