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


sr_gazebo_plugins
Author(s): adapted by Ugo(software@shadowrobot.com), Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Mon Oct 6 2014 07:58:14