Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <fstream>
00031 #include <iostream>
00032 #include <math.h>
00033 #include <unistd.h>
00034 #include <set>
00035
00036 #include <map>
00037
00038 #include <angles/angles.h>
00039 #include <urdf/model.h>
00040
00041
00042
00043 #include <gazebo/physics/physics.hh>
00044 #include <gazebo/sensors/sensors.hh>
00045 #include <gazebo/common/common.hh>
00046 #include <sdf/sdf.hh>
00047 #include <sdf/Param.hh>
00048
00049 #include "pr2_gazebo_plugins/gazebo_ros_controller_manager.h"
00050
00051 namespace gazebo {
00052
00053 GazeboRosControllerManager::GazeboRosControllerManager()
00054 {
00055 }
00056
00058 bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req,
00059 pr2_gazebo_plugins::SetModelsJointsStates::Response &res)
00060 {
00061
00062 return true;
00063 }
00064
00065
00066 GazeboRosControllerManager::~GazeboRosControllerManager()
00067 {
00068 ROS_DEBUG("Calling FiniChild in GazeboRosControllerManager");
00069
00070
00071
00072
00073 this->cm_->~ControllerManager();
00074 this->rosnode_->shutdown();
00075 #ifdef USE_CBQ
00076 this->controller_manager_queue_.clear();
00077 this->controller_manager_queue_.disable();
00078 this->controller_manager_callback_queue_thread_.join();
00079 #endif
00080 this->ros_spinner_thread_.join();
00081
00082
00083
00084
00085 delete this->cm_;
00086 delete this->rosnode_;
00087
00088 if (this->fake_state_)
00089 {
00090
00091
00092 delete this->fake_state_;
00093 }
00094 }
00095
00096 void GazeboRosControllerManager::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00097 {
00098
00099 std::string modelName = _sdf->GetParent()->Get<std::string>("name");
00100
00101
00102 this->world = _parent->GetWorld();
00103
00104
00105 this->parent_model_ = _parent;
00106
00107
00108 if (!this->parent_model_)
00109 gzerr << "Unable to get parent model\n";
00110
00111
00112
00113 this->updateConnection = event::Events::ConnectWorldUpdateBegin(
00114 boost::bind(&GazeboRosControllerManager::UpdateChild, this));
00115 gzdbg << "plugin model name: " << modelName << "\n";
00116
00117
00118
00119
00120 if (getenv("CHECK_SPEEDUP"))
00121 {
00122 wall_start_ = this->world->GetRealTime().Double();
00123 sim_start_ = this->world->GetSimTime().Double();
00124 }
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137 this->robotNamespace = "";
00138 if (_sdf->HasElement("robotNamespace"))
00139 this->robotNamespace = _sdf->Get<std::string>("robotNamespace");
00140
00141 this->robotParam = "robot_description";
00142 if (_sdf->HasElement("robotParam"))
00143 this->robotParam = _sdf->Get<std::string>("robotParam");
00144
00145 this->robotParam = this->robotNamespace+"/" + this->robotParam;
00146
00147 if (!ros::isInitialized())
00148 {
00149 int argc = 0;
00150 char** argv = NULL;
00151 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00152 }
00153 this->rosnode_ = new ros::NodeHandle(this->robotNamespace);
00154 ROS_INFO("starting gazebo_ros_controller_manager plugin in ns: %s",this->robotNamespace.c_str());
00155
00156
00157 this->ros_spinner_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerROSThread,this ) );
00158
00159
00160
00161 this->cm_ = new pr2_controller_manager::ControllerManager(&hw_,*this->rosnode_);
00162 this->hw_.current_time_ = ros::Time(this->world->GetSimTime().Double());
00163 if (this->hw_.current_time_ < ros::Time(0.001)) this->hw_.current_time_ == ros::Time(0.001);
00164
00165 this->rosnode_->param("gazebo/start_robot_calibrated",this->fake_calibration_,true);
00166
00167
00168
00169 ReadPr2Xml();
00170
00171
00172 this->fake_state_ = new pr2_mechanism_model::RobotState(&this->cm_->model_);
00173
00174
00175 if (this->cm_->state_ != NULL)
00176 {
00177 for (unsigned int i = 0; i < this->cm_->state_->joint_states_.size(); ++i)
00178 {
00179 std::string joint_name = this->cm_->state_->joint_states_[i].joint_->name;
00180
00181
00182 gazebo::physics::JointPtr joint = this->parent_model_->GetJoint(joint_name);
00183 if (joint)
00184 {
00185 this->joints_.push_back(joint);
00186 }
00187 else
00188 {
00189
00190
00191 this->joints_.push_back(gazebo::physics::JointPtr());
00192 ROS_ERROR("A joint named \"%s\" is not part of Mechanism Controlled joints.\n", joint_name.c_str());
00193 }
00194
00195 }
00196 }
00197
00198 #ifdef USE_CBQ
00199
00200 this->controller_manager_callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosControllerManager::ControllerManagerQueueThread,this ) );
00201 #endif
00202
00203 }
00204
00205
00206 void GazeboRosControllerManager::UpdateChild()
00207 {
00208 if (this->world->IsPaused()) return;
00209
00210 if (getenv("CHECK_SPEEDUP"))
00211 {
00212 double wall_elapsed = this->world->GetRealTime().Double() - wall_start_;
00213 double sim_elapsed = this->world->GetSimTime().Double() - sim_start_;
00214 std::cout << " real time: " << wall_elapsed
00215 << " sim time: " << sim_elapsed
00216 << " speed up: " << sim_elapsed / wall_elapsed
00217 << std::endl;
00218 }
00219 assert(this->joints_.size() == this->fake_state_->joint_states_.size());
00220
00221
00222
00223
00224
00225
00226
00227 for (unsigned int i = 0; i < this->joints_.size(); ++i)
00228 {
00229 if (!this->joints_[i])
00230 continue;
00231
00232 this->fake_state_->joint_states_[i].measured_effort_ = this->fake_state_->joint_states_[i].commanded_effort_;
00233
00234 if (this->joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT))
00235 {
00236 gazebo::physics::JointPtr hj = this->joints_[i];
00237 this->fake_state_->joint_states_[i].position_ = this->fake_state_->joint_states_[i].position_ +
00238 angles::shortest_angular_distance(this->fake_state_->joint_states_[i].position_,hj->GetAngle(0).Radian());
00239 this->fake_state_->joint_states_[i].velocity_ = hj->GetVelocity(0);
00240
00241
00242 }
00243 else if (this->joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT))
00244 {
00245 gazebo::physics::JointPtr sj = this->joints_[i];
00246 {
00247 this->fake_state_->joint_states_[i].position_ = sj->GetAngle(0).Radian();
00248 this->fake_state_->joint_states_[i].velocity_ = sj->GetVelocity(0);
00249 }
00250
00251
00252
00253 }
00254 else
00255 {
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265 }
00266 }
00267
00268
00269 this->fake_state_->propagateJointPositionToActuatorPosition();
00270
00271
00272
00273
00274 this->hw_.current_time_ = ros::Time(this->world->GetSimTime().Double());
00275 try
00276 {
00277 if (this->cm_->state_ != NULL)
00278 this->cm_->update();
00279 }
00280 catch (const char* c)
00281 {
00282 if (strcmp(c,"dividebyzero")==0)
00283 ROS_WARN("pid controller reports divide by zero error");
00284 else
00285 ROS_WARN("unknown const char* exception: %s", c);
00286 }
00287
00288
00289
00290
00291
00292
00293 this->fake_state_->propagateActuatorEffortToJointEffort();
00294
00295
00296 for (unsigned int i = 0; i < this->joints_.size(); ++i)
00297 {
00298 if (!this->joints_[i])
00299 continue;
00300
00301 double effort = this->fake_state_->joint_states_[i].commanded_effort_;
00302
00303 double damping_coef = 0;
00304 if (this->cm_->state_ != NULL)
00305 {
00306 if (this->cm_->state_->joint_states_[i].joint_->dynamics)
00307 damping_coef = this->cm_->state_->joint_states_[i].joint_->dynamics->damping;
00308 }
00309
00310 if (this->joints_[i]->HasType(gazebo::physics::Base::HINGE_JOINT))
00311 {
00312 gazebo::physics::JointPtr hj = this->joints_[i];
00313 double current_velocity = hj->GetVelocity(0);
00314 double damping_force = damping_coef * current_velocity;
00315 double effort_command = effort - damping_force;
00316 hj->SetForce(0,effort_command);
00317
00318
00319 }
00320 else if (this->joints_[i]->HasType(gazebo::physics::Base::SLIDER_JOINT))
00321 {
00322 gazebo::physics::JointPtr sj = this->joints_[i];
00323 double current_velocity = sj->GetVelocity(0);
00324 double damping_force = damping_coef * current_velocity;
00325 double effort_command = effort-damping_force;
00326 sj->SetForce(0,effort_command);
00327
00328
00329 }
00330 }
00331 }
00332
00333
00334 void GazeboRosControllerManager::ReadPr2Xml()
00335 {
00336
00337 std::string urdf_param_name;
00338 std::string urdf_string;
00339
00340 while(urdf_string.empty())
00341 {
00342 ROS_INFO("gazebo controller manager plugin is waiting for urdf: %s on the param server. (make sure there is a rosparam by that name in the ros parameter server, otherwise, this plugin blocks simulation forever).", this->robotParam.c_str());
00343 if (this->rosnode_->searchParam(this->robotParam,urdf_param_name))
00344 {
00345 this->rosnode_->getParam(urdf_param_name,urdf_string);
00346 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());
00347 }
00348 else
00349 {
00350 this->rosnode_->getParam(this->robotParam,urdf_string);
00351 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());
00352 }
00353 usleep(100000);
00354 }
00355 ROS_INFO("gazebo controller manager got pr2.xml from param server, parsing it...");
00356
00357
00358 TiXmlDocument doc;
00359 if (!doc.Parse(urdf_string.c_str()) && doc.Error())
00360 {
00361 ROS_ERROR("Could not load the gazebo controller manager plugin's configuration file: %s\n",
00362 urdf_string.c_str());
00363 }
00364 else
00365 {
00366
00367
00368
00369
00370 struct GetActuators : public TiXmlVisitor
00371 {
00372 std::set<std::string> actuators;
00373 virtual bool VisitEnter(const TiXmlElement &elt, const TiXmlAttribute *)
00374 {
00375 if (elt.ValueStr() == std::string("actuator") && elt.Attribute("name"))
00376 actuators.insert(elt.Attribute("name"));
00377 else if (elt.ValueStr() == std::string("rightActuator") && elt.Attribute("name"))
00378 actuators.insert(elt.Attribute("name"));
00379 else if (elt.ValueStr() == std::string("leftActuator") && elt.Attribute("name"))
00380 actuators.insert(elt.Attribute("name"));
00381 return true;
00382 }
00383 } get_actuators;
00384 doc.RootElement()->Accept(&get_actuators);
00385
00386
00387 std::set<std::string>::iterator it;
00388 for (it = get_actuators.actuators.begin(); it != get_actuators.actuators.end(); ++it)
00389 {
00390
00391 pr2_hardware_interface::Actuator* pr2_actuator = new pr2_hardware_interface::Actuator(*it);
00392 pr2_actuator->state_.is_enabled_ = true;
00393 this->hw_.addActuator(pr2_actuator);
00394 }
00395
00396
00397 this->cm_->initXml(doc.RootElement());
00398
00399 for (unsigned int i = 0; i < this->cm_->state_->joint_states_.size(); ++i)
00400 this->cm_->state_->joint_states_[i].calibrated_ = fake_calibration_;
00401 }
00402 }
00403
00404 #ifdef USE_CBQ
00405
00406
00407 void GazeboRosControllerManager::ControllerManagerQueueThread()
00408 {
00409 ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id());
00410
00411 static const double timeout = 0.01;
00412
00413 while (this->rosnode_->ok())
00414 {
00415 this->controller_manager_queue_.callAvailable(ros::WallDuration(timeout));
00416 }
00417 }
00418 #endif
00419
00420 void GazeboRosControllerManager::ControllerManagerROSThread()
00421 {
00422 ROS_INFO_STREAM("Callback thread id=" << boost::this_thread::get_id());
00423
00424
00425
00426 while (this->rosnode_->ok())
00427 {
00428
00429 usleep(1000);
00430 ros::spinOnce();
00431 }
00432 }
00433
00434 GZ_REGISTER_MODEL_PLUGIN(GazeboRosControllerManager)
00435 }