gazebo_ros_api_plugin.cpp
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 
00022 /* Desc: External interfaces for Gazebo
00023  * Author: John Hsu adapted original gazebo main.cc by Nate Koenig
00024  * Date: 25 Apr 2010
00025  * SVN: $Id: main.cc 8598 2010-03-22 21:59:24Z hsujohnhsu $
00026  */
00027 
00028 #include "common/Events.hh"
00029 #include <gazebo/gazebo_ros_api_plugin.h>
00030 #include <gazebo/urdf2gazebo.h>
00031 
00032 namespace gazebo
00033 {
00034 
00035     GazeboRosApiPlugin::GazeboRosApiPlugin()
00036     {
00037       this->world_created_ = false;
00038     }
00039 
00040     GazeboRosApiPlugin::~GazeboRosApiPlugin()
00041     {
00042       // disconnect slots
00043       gazebo::event::Events::DisconnectWorldUpdateStart(this->wrench_update_event_);
00044       gazebo::event::Events::DisconnectWorldUpdateStart(this->force_update_event_);
00045       gazebo::event::Events::DisconnectWorldUpdateStart(this->time_update_event_);
00046 
00047       if (this->pub_link_states_connection_count_ > 0) // disconnect if there are subscribers on exit
00048         gazebo::event::Events::DisconnectWorldUpdateStart(this->pub_link_states_event_);
00049       if (this->pub_model_states_connection_count_ > 0) // disconnect if there are subscribers on exit
00050         gazebo::event::Events::DisconnectWorldUpdateStart(this->pub_model_states_event_);
00051 
00052       // shutdown ros
00053       this->rosnode_->shutdown();
00054       delete this->rosnode_;
00055 
00056       // shutdown ros queue
00057       this->gazebo_callback_queue_thread_->join();
00058       delete this->gazebo_callback_queue_thread_;
00059 
00060       this->physics_reconfigure_thread_->join();
00061       delete this->physics_reconfigure_thread_;
00062 
00063       this->ros_spin_thread_->join();
00064       delete this->ros_spin_thread_;
00065 
00066       /* Delete Force and Wrench Jobs */
00067       this->lock_.lock();
00068       for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=this->force_joint_jobs.begin();iter!=this->force_joint_jobs.end();)
00069       {
00070         delete (*iter);
00071         this->force_joint_jobs.erase(iter);
00072       }
00073       for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=this->wrench_body_jobs.begin();iter!=this->wrench_body_jobs.end();)
00074       {
00075         delete (*iter);
00076         this->wrench_body_jobs.erase(iter);
00077       }
00078       this->lock_.unlock();
00079     }
00080 
00081     void GazeboRosApiPlugin::Load(int argc, char** argv)
00082     {
00083       // setup ros related
00084       if (!ros::isInitialized())
00085         ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler);
00086       else
00087         ROS_ERROR("Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
00088 
00089       this->rosnode_ = new ros::NodeHandle("~");
00090 
00092       gazebo_callback_queue_thread_ = new boost::thread( &GazeboRosApiPlugin::gazeboQueueThread,this );
00093 
00095       this->physics_reconfigure_thread_ = new boost::thread(boost::bind(&GazeboRosApiPlugin::PhysicsReconfigureNode, this));
00096       this->physics_reconfigure_initialized_ = false;
00097 
00098       // below needs the world to be created first
00099       this->load_gazebo_ros_api_plugin_event_ = gazebo::event::Events::ConnectWorldCreated(boost::bind(&GazeboRosApiPlugin::LoadGazeboRosApiPlugin,this,_1));
00100     }
00101 
00102     void GazeboRosApiPlugin::LoadGazeboRosApiPlugin(std::string _worldName)
00103     {
00104       // make sure things are only called once
00105       gazebo::event::Events::DisconnectWorldCreated(this->load_gazebo_ros_api_plugin_event_);
00106       this->lock_.lock();
00107       if (this->world_created_)
00108       {
00109         this->lock_.unlock();
00110         return;
00111       }
00112 
00113       // set flag to true and load this plugin
00114       this->world_created_ = true;
00115       this->lock_.unlock();
00116 
00117 
00118       this->world = gazebo::physics::get_world(_worldName);
00119       if (!this->world)
00120       {
00121         //ROS_ERROR("world name: [%s]",this->world->GetName().c_str());
00122         // connect helper function to signal for scheduling torque/forces, etc
00123         ROS_FATAL("cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
00124         return;
00125       }
00126 
00127       this->gazebonode_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
00128       this->gazebonode_->Init(_worldName);
00129       //this->stat_sub_ = this->gazebonode_->Subscribe("~/world_stats", &GazeboRosApiPlugin::publishSimTime, this); // TODO: does not work in server plugin?
00130       this->factory_pub_ = this->gazebonode_->Advertise<gazebo::msgs::Factory>("~/factory");
00131       this->request_pub_ = this->gazebonode_->Advertise<gazebo::msgs::Request>("~/request");
00132       this->response_sub_ = this->gazebonode_->Subscribe("~/response",&GazeboRosApiPlugin::OnResponse, this);
00133 
00134       // reset topic connection counts
00135       this->pub_link_states_connection_count_ = 0;
00136       this->pub_model_states_connection_count_ = 0;
00137 
00139       this->AdvertiseServices();
00140 
00141       // hooks for applying forces, publishing simtime on /clock
00142       this->wrench_update_event_ = gazebo::event::Events::ConnectWorldUpdateStart(boost::bind(&GazeboRosApiPlugin::wrenchBodySchedulerSlot,this));
00143       this->force_update_event_  = gazebo::event::Events::ConnectWorldUpdateStart(boost::bind(&GazeboRosApiPlugin::forceJointSchedulerSlot,this));
00144       this->time_update_event_   = gazebo::event::Events::ConnectWorldUpdateStart(boost::bind(&GazeboRosApiPlugin::publishSimTime,this));
00145 
00146       // spin ros, is this needed?
00147       this->ros_spin_thread_ = new boost::thread(boost::bind(&GazeboRosApiPlugin::spin, this));
00148 
00149     }
00150 
00151     void GazeboRosApiPlugin::OnResponse(ConstResponsePtr &_response)
00152     {
00153       
00154     }
00155 
00157     void GazeboRosApiPlugin::gazeboQueueThread()
00158     {
00159       ROS_DEBUG_STREAM("Callback thread id=" << boost::this_thread::get_id());
00160       static const double timeout = 0.001;
00161       while (this->rosnode_->ok())
00162         this->gazebo_queue_.callAvailable(ros::WallDuration(timeout));
00163     }
00164 
00166     void GazeboRosApiPlugin::AdvertiseServices()
00167     {
00168       // publish clock for simulated ros time
00169       pub_clock_ = this->rosnode_->advertise<rosgraph_msgs::Clock>("/clock",10);
00170 
00171       // Advertise spawn services on the custom queue
00172       std::string spawn_gazebo_model_service_name("spawn_gazebo_model");
00173       ros::AdvertiseServiceOptions spawn_gazebo_model_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
00174           spawn_gazebo_model_service_name,boost::bind(&GazeboRosApiPlugin::spawnGazeboModel,this,_1,_2),
00175           ros::VoidPtr(), &this->gazebo_queue_);
00176       spawn_urdf_gazebo_service_ = this->rosnode_->advertiseService(spawn_gazebo_model_aso);
00177 
00178       // Advertise spawn services on the custom queue
00179       std::string spawn_urdf_model_service_name("spawn_urdf_model");
00180       ros::AdvertiseServiceOptions spawn_urdf_model_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
00181           spawn_urdf_model_service_name,boost::bind(&GazeboRosApiPlugin::spawnURDFModel,this,_1,_2),
00182           ros::VoidPtr(), &this->gazebo_queue_);
00183       spawn_urdf_model_service_ = this->rosnode_->advertiseService(spawn_urdf_model_aso);
00184 
00185       // Advertise delete services on the custom queue
00186       std::string delete_model_service_name("delete_model");
00187       ros::AdvertiseServiceOptions delete_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
00188           delete_model_service_name,boost::bind(&GazeboRosApiPlugin::deleteModel,this,_1,_2),
00189           ros::VoidPtr(), &this->gazebo_queue_);
00190       delete_model_service_ = this->rosnode_->advertiseService(delete_aso);
00191 
00192       // Advertise more services on the custom queue
00193       std::string get_model_properties_service_name("get_model_properties");
00194       ros::AdvertiseServiceOptions get_model_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
00195           get_model_properties_service_name,boost::bind(&GazeboRosApiPlugin::getModelProperties,this,_1,_2),
00196           ros::VoidPtr(), &this->gazebo_queue_);
00197       get_model_properties_service_ = this->rosnode_->advertiseService(get_model_properties_aso);
00198 
00199       // Advertise more services on the custom queue
00200       std::string get_model_state_service_name("get_model_state");
00201       ros::AdvertiseServiceOptions get_model_state_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
00202           get_model_state_service_name,boost::bind(&GazeboRosApiPlugin::getModelState,this,_1,_2),
00203           ros::VoidPtr(), &this->gazebo_queue_);
00204       get_model_state_service_ = this->rosnode_->advertiseService(get_model_state_aso);
00205 
00206       // Advertise more services on the custom queue
00207       std::string get_world_properties_service_name("get_world_properties");
00208       ros::AdvertiseServiceOptions get_world_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
00209           get_world_properties_service_name,boost::bind(&GazeboRosApiPlugin::getWorldProperties,this,_1,_2),
00210           ros::VoidPtr(), &this->gazebo_queue_);
00211       get_world_properties_service_ = this->rosnode_->advertiseService(get_world_properties_aso);
00212 
00213       // Advertise more services on the custom queue
00214       std::string get_joint_properties_service_name("get_joint_properties");
00215       ros::AdvertiseServiceOptions get_joint_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
00216           get_joint_properties_service_name,boost::bind(&GazeboRosApiPlugin::getJointProperties,this,_1,_2),
00217           ros::VoidPtr(), &this->gazebo_queue_);
00218       get_joint_properties_service_ = this->rosnode_->advertiseService(get_joint_properties_aso);
00219 
00220       // Advertise more services on the custom queue
00221       std::string get_link_properties_service_name("get_link_properties");
00222       ros::AdvertiseServiceOptions get_link_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
00223           get_link_properties_service_name,boost::bind(&GazeboRosApiPlugin::getLinkProperties,this,_1,_2),
00224           ros::VoidPtr(), &this->gazebo_queue_);
00225       get_link_properties_service_ = this->rosnode_->advertiseService(get_link_properties_aso);
00226 
00227       // Advertise more services on the custom queue
00228       std::string get_link_state_service_name("get_link_state");
00229       ros::AdvertiseServiceOptions get_link_state_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
00230           get_link_state_service_name,boost::bind(&GazeboRosApiPlugin::getLinkState,this,_1,_2),
00231           ros::VoidPtr(), &this->gazebo_queue_);
00232       get_link_state_service_ = this->rosnode_->advertiseService(get_link_state_aso);
00233 
00234       // Advertise more services on the custom queue
00235       std::string set_link_properties_service_name("set_link_properties");
00236       ros::AdvertiseServiceOptions set_link_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
00237           set_link_properties_service_name,boost::bind(&GazeboRosApiPlugin::setLinkProperties,this,_1,_2),
00238           ros::VoidPtr(), &this->gazebo_queue_);
00239       set_link_properties_service_ = this->rosnode_->advertiseService(set_link_properties_aso);
00240 
00241       // Advertise more services on the custom queue
00242       std::string set_physics_properties_service_name("set_physics_properties");
00243       ros::AdvertiseServiceOptions set_physics_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
00244           set_physics_properties_service_name,boost::bind(&GazeboRosApiPlugin::setPhysicsProperties,this,_1,_2),
00245           ros::VoidPtr(), &this->gazebo_queue_);
00246       set_physics_properties_service_ = this->rosnode_->advertiseService(set_physics_properties_aso);
00247 
00248       // Advertise more services on the custom queue
00249       std::string get_physics_properties_service_name("get_physics_properties");
00250       ros::AdvertiseServiceOptions get_physics_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
00251           get_physics_properties_service_name,boost::bind(&GazeboRosApiPlugin::getPhysicsProperties,this,_1,_2),
00252           ros::VoidPtr(), &this->gazebo_queue_);
00253       get_physics_properties_service_ = this->rosnode_->advertiseService(get_physics_properties_aso);
00254 
00255       // Advertise more services on the custom queue
00256       std::string apply_body_wrench_service_name("apply_body_wrench");
00257       ros::AdvertiseServiceOptions apply_body_wrench_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
00258           apply_body_wrench_service_name,boost::bind(&GazeboRosApiPlugin::applyBodyWrench,this,_1,_2),
00259           ros::VoidPtr(), &this->gazebo_queue_);
00260       apply_body_wrench_service_ = this->rosnode_->advertiseService(apply_body_wrench_aso);
00261 
00262       // Advertise more services on the custom queue
00263       std::string set_model_state_service_name("set_model_state");
00264       ros::AdvertiseServiceOptions set_model_state_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
00265           set_model_state_service_name,boost::bind(&GazeboRosApiPlugin::setModelState,this,_1,_2),
00266           ros::VoidPtr(), &this->gazebo_queue_);
00267       set_model_state_service_ = this->rosnode_->advertiseService(set_model_state_aso);
00268 
00269       // Advertise more services on the custom queue
00270       std::string apply_joint_effort_service_name("apply_joint_effort");
00271       ros::AdvertiseServiceOptions apply_joint_effort_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
00272           apply_joint_effort_service_name,boost::bind(&GazeboRosApiPlugin::applyJointEffort,this,_1,_2),
00273           ros::VoidPtr(), &this->gazebo_queue_);
00274       apply_joint_effort_service_ = this->rosnode_->advertiseService(apply_joint_effort_aso);
00275 
00276       // Advertise more services on the custom queue
00277       std::string set_joint_properties_service_name("set_joint_properties");
00278       ros::AdvertiseServiceOptions set_joint_properties_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
00279           set_joint_properties_service_name,boost::bind(&GazeboRosApiPlugin::setJointProperties,this,_1,_2),
00280           ros::VoidPtr(), &this->gazebo_queue_);
00281       set_joint_properties_service_ = this->rosnode_->advertiseService(set_joint_properties_aso);
00282 
00283       // Advertise more services on the custom queue
00284       std::string set_model_configuration_service_name("set_model_configuration");
00285       ros::AdvertiseServiceOptions set_model_configuration_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
00286           set_model_configuration_service_name,boost::bind(&GazeboRosApiPlugin::setModelConfiguration,this,_1,_2),
00287           ros::VoidPtr(), &this->gazebo_queue_);
00288       set_model_configuration_service_ = this->rosnode_->advertiseService(set_model_configuration_aso);
00289 
00290       // Advertise more services on the custom queue
00291       std::string set_link_state_service_name("set_link_state");
00292       ros::AdvertiseServiceOptions set_link_state_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
00293           set_link_state_service_name,boost::bind(&GazeboRosApiPlugin::setLinkState,this,_1,_2),
00294           ros::VoidPtr(), &this->gazebo_queue_);
00295       set_link_state_service_ = this->rosnode_->advertiseService(set_link_state_aso);
00296 
00297       // Advertise more services on the custom queue
00298       std::string reset_simulation_service_name("reset_simulation");
00299       ros::AdvertiseServiceOptions reset_simulation_aso = ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00300           reset_simulation_service_name,boost::bind(&GazeboRosApiPlugin::resetSimulation,this,_1,_2),
00301           ros::VoidPtr(), &this->gazebo_queue_);
00302       reset_simulation_service_ = this->rosnode_->advertiseService(reset_simulation_aso);
00303 
00304       // Advertise more services on the custom queue
00305       std::string reset_world_service_name("reset_world");
00306       ros::AdvertiseServiceOptions reset_world_aso = ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00307           reset_world_service_name,boost::bind(&GazeboRosApiPlugin::resetWorld,this,_1,_2),
00308           ros::VoidPtr(), &this->gazebo_queue_);
00309       reset_world_service_ = this->rosnode_->advertiseService(reset_world_aso);
00310 
00311       // Advertise more services on the custom queue
00312       std::string pause_physics_service_name("pause_physics");
00313       ros::AdvertiseServiceOptions pause_physics_aso = ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00314           pause_physics_service_name,boost::bind(&GazeboRosApiPlugin::pausePhysics,this,_1,_2),
00315           ros::VoidPtr(), &this->gazebo_queue_);
00316       pause_physics_service_ = this->rosnode_->advertiseService(pause_physics_aso);
00317 
00318       // Advertise more services on the custom queue
00319       std::string unpause_physics_service_name("unpause_physics");
00320       ros::AdvertiseServiceOptions unpause_physics_aso = ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00321           unpause_physics_service_name,boost::bind(&GazeboRosApiPlugin::unpausePhysics,this,_1,_2),
00322           ros::VoidPtr(), &this->gazebo_queue_);
00323       unpause_physics_service_ = this->rosnode_->advertiseService(unpause_physics_aso);
00324 
00325       // Advertise more services on the custom queue
00326       std::string clear_joint_forces_service_name("clear_joint_forces");
00327       ros::AdvertiseServiceOptions clear_joint_forces_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
00328           clear_joint_forces_service_name,boost::bind(&GazeboRosApiPlugin::clearJointForces,this,_1,_2),
00329           ros::VoidPtr(), &this->gazebo_queue_);
00330       clear_joint_forces_service_ = this->rosnode_->advertiseService(clear_joint_forces_aso);
00331 
00332       // Advertise more services on the custom queue
00333       std::string clear_body_wrenches_service_name("clear_body_wrenches");
00334       ros::AdvertiseServiceOptions clear_body_wrenches_aso = ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
00335           clear_body_wrenches_service_name,boost::bind(&GazeboRosApiPlugin::clearBodyWrenches,this,_1,_2),
00336           ros::VoidPtr(), &this->gazebo_queue_);
00337       clear_body_wrenches_service_ = this->rosnode_->advertiseService(clear_body_wrenches_aso);
00338 
00339       // Advertise topic on custom queue
00340       // topic callback version for set_link_state
00341       ros::SubscribeOptions link_state_so = ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
00342         "set_link_state",10, boost::bind( &GazeboRosApiPlugin::updateLinkState,this,_1),
00343         ros::VoidPtr(), &this->gazebo_queue_);
00344       set_link_state_topic_ = this->rosnode_->subscribe(link_state_so);
00345 
00346       // topic callback version for set_model_state
00347       ros::SubscribeOptions model_state_so = ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
00348         "set_model_state",10, boost::bind( &GazeboRosApiPlugin::updateModelState,this,_1),
00349         ros::VoidPtr(), &this->gazebo_queue_);
00350       set_model_state_topic_ = this->rosnode_->subscribe(model_state_so);
00351 
00352       // publish complete link states in world frame
00353       ros::AdvertiseOptions pub_link_states_ao = ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
00354         "link_states",10,
00355         boost::bind(&GazeboRosApiPlugin::onLinkStatesConnect,this),
00356         boost::bind(&GazeboRosApiPlugin::onLinkStatesDisconnect,this), ros::VoidPtr(), &this->gazebo_queue_);
00357       pub_link_states_ = this->rosnode_->advertise(pub_link_states_ao);
00358 
00359       // publish complete model states in world frame
00360       ros::AdvertiseOptions pub_model_states_ao = ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
00361         "model_states",10,
00362         boost::bind(&GazeboRosApiPlugin::onModelStatesConnect,this),
00363         boost::bind(&GazeboRosApiPlugin::onModelStatesDisconnect,this), ros::VoidPtr(), &this->gazebo_queue_);
00364       pub_model_states_ = this->rosnode_->advertise(pub_model_states_ao);
00365 
00366       // set param for use_sim_time if not set by user alread
00367       this->rosnode_->setParam("/use_sim_time", true);
00368 
00369       // todo: contemplate setting environment variable ROBOT=sim here???
00370 
00371     }
00372 
00373     void GazeboRosApiPlugin::onLinkStatesConnect()
00374     {
00375       this->pub_link_states_connection_count_++;
00376       if (this->pub_link_states_connection_count_ == 1) // connect on first subscriber
00377         this->pub_link_states_event_   = gazebo::event::Events::ConnectWorldUpdateStart(boost::bind(&GazeboRosApiPlugin::publishLinkStates,this));
00378     }
00379     void GazeboRosApiPlugin::onModelStatesConnect()
00380     {
00381       this->pub_model_states_connection_count_++;
00382       if (this->pub_model_states_connection_count_ == 1) // connect on first subscriber
00383         this->pub_model_states_event_   = gazebo::event::Events::ConnectWorldUpdateStart(boost::bind(&GazeboRosApiPlugin::publishModelStates,this));
00384     }
00385     void GazeboRosApiPlugin::onLinkStatesDisconnect()
00386     {
00387       this->pub_link_states_connection_count_--;
00388       if (this->pub_link_states_connection_count_ <= 0) // disconnect with no subscribers
00389       {
00390         gazebo::event::Events::DisconnectWorldUpdateStart(this->pub_link_states_event_);
00391         if (this->pub_link_states_connection_count_ < 0) // should not be possible
00392           ROS_ERROR("one too mandy disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
00393       }
00394     }
00395     void GazeboRosApiPlugin::onModelStatesDisconnect()
00396     {
00397       this->pub_model_states_connection_count_--;
00398       if (this->pub_model_states_connection_count_ <= 0) // disconnect with no subscribers
00399       {
00400         gazebo::event::Events::DisconnectWorldUpdateStart(this->pub_model_states_event_);
00401         if (this->pub_model_states_connection_count_ < 0) // should not be possible
00402           ROS_ERROR("one too mandy disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
00403       }
00404     }
00405 
00406     bool GazeboRosApiPlugin::spawnURDFModel(gazebo_msgs::SpawnModel::Request &req,gazebo_msgs::SpawnModel::Response &res)
00407     {
00408       // get flag on joint limits
00409       bool enforce_limits = true; //option to add req.enforce_limits??
00410 
00411       // get name space for the corresponding model plugins
00412       std::string robot_namespace = req.robot_namespace;
00413 
00414       // incoming robot name
00415       std::string model_name = req.model_name;
00416 
00417       // incoming robot model string
00418       std::string model_xml = req.model_xml;
00419 
00420       if (!this->IsURDF(model_xml))
00421       {
00422         ROS_ERROR("SpawnModel: Failure - model format is not URDF.");
00423         res.success = false;
00424         res.status_message = "SpawnModel: Failure - model format is not URDF.";
00425         return false;
00426       }
00427 
00431       std::string open_bracket("<?");
00432       std::string close_bracket("?>");
00433       size_t pos1 = model_xml.find(open_bracket,0);
00434       size_t pos2 = model_xml.find(close_bracket,0);
00435       if (pos1 != std::string::npos && pos2 != std::string::npos)
00436         model_xml.replace(pos1,pos2-pos1+2,std::string(""));
00437 
00438       ROS_DEBUG("Model XML\n\n%s\n\n ",model_xml.c_str());
00439 
00440       urdf2gazebo::URDF2Gazebo u2g;
00441       TiXmlDocument model_xml_doc;
00442       model_xml_doc.Parse(model_xml.c_str());
00443       TiXmlDocument gazebo_model_xml;
00444       // initial xyz and rpy are empty, will be inserted in spawnGazeboModel
00445       if (!u2g.convert(model_xml_doc, gazebo_model_xml, enforce_limits, urdf::Vector3(), urdf::Vector3(), model_name, robot_namespace))
00446       {
00447         // set result
00448         res.success = false;
00449         res.status_message = std::string("SpawnModel: urdf2gazebo conversion failed.");
00450         return false;
00451       }
00452 
00453       // push to factory iface
00454       std::ostringstream stream;
00455       stream << gazebo_model_xml;
00456       std::string gazebo_model_xml_string = stream.str();
00457       ROS_DEBUG("Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
00458       req.model_xml = gazebo_model_xml_string;
00459 
00460       // publish gazebo model on parameter server as [robot_namespace]/gazebo/[model name]/robot_description
00461       // this->rosnode_->setParam(robot_namespace+std::string("/gazebo/")+model_name+std::string("/robot_description"),gazebo_model_xml_string);
00462 
00463       return spawnGazeboModel(req,res);
00464     }
00465 
00466     bool GazeboRosApiPlugin::spawnGazeboModel(gazebo_msgs::SpawnModel::Request &req,gazebo_msgs::SpawnModel::Response &res)
00467     {
00468       // incoming robot name
00469       std::string model_name = req.model_name;
00470 
00471       // get name space for the corresponding model plugins
00472       std::string robot_namespace = req.robot_namespace;
00473 
00474       // get initial pose of model
00475       gazebo::math::Vector3 initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
00476       // get initial roll pitch yaw (fixed frame transform)
00477       gazebo::math::Quaternion initial_q(req.initial_pose.orientation.w,req.initial_pose.orientation.x,req.initial_pose.orientation.y,req.initial_pose.orientation.z);
00478 
00479       // refernce frame for initial pose definition, modify initial pose if defined
00480       gazebo::physics::LinkPtr frame = boost::shared_dynamic_cast<gazebo::physics::Link>(this->world->GetEntity(req.reference_frame));
00481       if (frame)
00482       {
00483         // convert to relative pose
00484         gazebo::math::Pose frame_pose = frame->GetWorldPose();
00485         initial_xyz = frame_pose.rot.RotateVector(initial_xyz);
00486         initial_xyz += frame_pose.pos;
00487         initial_q *= frame_pose.rot;
00488       }
00489 
00491       else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
00492       {
00493           ROS_DEBUG("SpawnModel: reference_frame is empty/world/map, using inertial frame");
00494       }
00495       else
00496       {
00497         res.success = false;
00498         res.status_message = "SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
00499         return false;
00500       }
00501 
00502       // incoming robot model string
00503       std::string model_xml = req.model_xml;
00504 
00505       // store resulting Gazebo Model XML to be sent to spawn queue
00506       // get incoming string containg either an URDF or a Gazebo Model XML
00507       // grab from parameter server if necessary
00508       // convert to Gazebo Model XML if necessary
00509       if (!this->IsGazeboModelXML(model_xml) && !IsSDF(model_xml))
00510       {
00511         ROS_ERROR("GazeboRosApiPlugin SpawnModel Failure: input model_xml not Gazebo XML, or cannot be converted to Gazebo XML");
00512         res.success = false;
00513         res.status_message = std::string("GazeboRosApiPlugin SpawnModel Failure: input model_xml not Gazebo XML, or cannot be converted to Gazebo XML");
00514         return false;
00515       }
00516 
00517 
00518       // incoming robot model string is a string containing a Gazebo Model XML
00522       std::string open_bracket("<?");
00523       std::string close_bracket("?>");
00524       size_t pos1 = model_xml.find(open_bracket,0);
00525       size_t pos2 = model_xml.find(close_bracket,0);
00526       if (pos1 != std::string::npos && pos2 != std::string::npos)
00527         model_xml.replace(pos1,pos2-pos1+2,std::string(""));
00528 
00529       // put string in TiXmlDocument for manipulation
00530       TiXmlDocument gazebo_model_xml;
00531       gazebo_model_xml.Parse(model_xml.c_str());
00532 
00533       // optional model manipulations:
00534       //  * update initial pose
00535       //  * replace model name
00536       if (gazebo_model_xml.FirstChildElement("model:physical")) // old gazebo pre 1.0.0
00537       {
00538         TiXmlElement* model_tixml = gazebo_model_xml.FirstChildElement("model:physical"); // old gazebo pre 1.0.0
00539         // replace initial pose of robot
00540         // find first instance of xyz and rpy, replace with initial pose
00541         TiXmlElement* xyz_key = model_tixml->FirstChildElement("xyz");
00542         if (xyz_key)
00543           model_tixml->RemoveChild(xyz_key);
00544         TiXmlElement* rpy_key = model_tixml->FirstChildElement("rpy");
00545         if (rpy_key)
00546           model_tixml->RemoveChild(rpy_key);
00547 
00548         xyz_key = new TiXmlElement("xyz");
00549         rpy_key = new TiXmlElement("rpy");
00550 
00551         std::ostringstream xyz_stream, rpy_stream;
00552         xyz_stream << initial_xyz.x << " " << initial_xyz.y << " " << initial_xyz.z;
00553         gazebo::math::Vector3 initial_rpy = initial_q.GetAsEuler(); // convert to Euler angles for Gazebo XML
00554         rpy_stream << initial_rpy.x*180.0/M_PI << " " << initial_rpy.y*180.0/M_PI << " " << initial_rpy.z*180.0/M_PI; // convert to degrees for Gazebo (though ROS is in Radians)
00555 
00556 
00557         TiXmlText* xyz_txt = new TiXmlText(xyz_stream.str());
00558         TiXmlText* rpy_txt = new TiXmlText(rpy_stream.str());
00559 
00560         xyz_key->LinkEndChild(xyz_txt);
00561         rpy_key->LinkEndChild(rpy_txt);
00562 
00563         model_tixml->LinkEndChild(xyz_key);
00564         model_tixml->LinkEndChild(rpy_key);
00565 
00566         // replace model name if one is specified by the user
00567         model_tixml->RemoveAttribute("name");
00568         model_tixml->SetAttribute("name",model_name);
00569 
00570       }
00571       else if (gazebo_model_xml.FirstChildElement("gazebo")) // is sdf
00572       {
00573         TiXmlElement* model_tixml = (gazebo_model_xml.FirstChildElement("gazebo"))->FirstChildElement("model");
00574         if (model_tixml)
00575         {
00576           // replace initial pose of robot
00577           // find first instance of xyz and rpy, replace with initial pose
00578           TiXmlElement* origin_key = model_tixml->FirstChildElement("origin");
00579 
00580           if (!origin_key)
00581           {
00582             origin_key = new TiXmlElement("origin");
00583             model_tixml->LinkEndChild(origin_key);
00584           }
00585 
00586           std::ostringstream origin_stream;
00587           gazebo::math::Vector3 initial_rpy = initial_q.GetAsEuler(); // convert to Euler angles for Gazebo XML
00588           origin_stream << initial_xyz.x << " " << initial_xyz.y << " " << initial_xyz.z << " "
00589                         << initial_rpy.x << " " << initial_rpy.y << " " << initial_rpy.z;
00590 
00591           origin_key->SetAttribute("pose",origin_stream.str());
00592 
00593           // replace model name if one is specified by the user
00594           model_tixml->RemoveAttribute("name");
00595           model_tixml->SetAttribute("name",model_name);
00596         }
00597         else
00598           ROS_WARN("could not find <model> element in sdf, so name and initial position is not applied");
00599       }
00600       else
00601         ROS_WARN("could not find <model> element, so name and initial position is not applied");
00602 
00603       // push to factory iface
00604       std::ostringstream stream;
00605       stream << gazebo_model_xml;
00606       std::string gazebo_model_xml_string = stream.str();
00607       ROS_DEBUG("Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
00608 
00609       // publish to factory topic
00610       gazebo::msgs::Factory msg;
00611       gazebo::msgs::Init(msg, "spawn_model");
00612       msg.set_sdf( gazebo_model_xml_string );
00613 
00614       //ROS_ERROR("attempting to spawn model name [%s] [%s]", model_name.c_str(),gazebo_model_xml_string.c_str());
00615 
00616       // FIXME: should use entity_info or add lock to World::receiveMutex
00617       // looking for Model to see if it exists already
00618       gazebo::msgs::Request *entity_info_msg = gazebo::msgs::CreateRequest("entity_info",req.model_name);
00619       this->request_pub_->Publish(*entity_info_msg,true);
00620       // todo: should wait for response response_sub_, check to see that if _msg->response == "nonexistant"
00621       
00622       gazebo::physics::ModelPtr model = this->world->GetModel(model_name);
00623       if (model)
00624       {
00625         ROS_ERROR("SpawnModel: Failure - model name %s already exist.",model_name.c_str());
00626         res.success = false;
00627         res.status_message = "SpawnModel: Failure - model already exists.";
00628         return false;
00629       }
00630 
00631       // Publish the factory message
00632       this->factory_pub_->Publish(msg);
00633 
00636 
00638       ros::Duration model_spawn_timeout(60.0);
00639       ros::Time timeout = ros::Time::now() + model_spawn_timeout;
00640       while (true)
00641       {
00642         if (ros::Time::now() > timeout)
00643         {
00644           res.success = false;
00645           res.status_message = std::string("SpawnModel: Model pushed to spawn queue, but spawn service timed out waiting for model to appear in simulation");
00646           return false;
00647         }
00648         {
00649           //boost::recursive_mutex::scoped_lock lock(*this->world->GetMRMutex());
00650           if (this->world->GetModel(model_name)) break;
00651         }
00652         ROS_DEBUG("Waiting for spawning model (%s)",model_name.c_str());
00653         usleep(1000);
00654       }
00655 
00656       // set result
00657       res.success = true;
00658       res.status_message = std::string("SpawnModel: successfully spawned model");
00659       return true;
00660     }
00661 
00664     bool GazeboRosApiPlugin::deleteModel(gazebo_msgs::DeleteModel::Request &req,gazebo_msgs::DeleteModel::Response &res)
00665     {
00666 
00667       // clear forces, etc for the body in question
00668       gazebo::physics::ModelPtr model = this->world->GetModel(req.model_name);
00669       if (!model)
00670       {
00671         ROS_ERROR("DeleteModel: model [%s] does not exist",req.model_name.c_str());
00672         res.success = false;
00673         res.status_message = "DeleteModel: model does not exist";
00674         return false;
00675       }
00676 
00677       // delete wrench jobs on bodies
00678       for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
00679       {
00680         gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
00681         if (body)
00682         {
00683           // look for it in jobs, delete body wrench jobs
00684           this->clearBodyWrenches(body->GetScopedName());
00685         }
00686       }
00687 
00688       // delete force jobs on joints
00689       for (unsigned int i=0;i< model->GetJointCount(); i++)
00690       {
00691         gazebo::physics::JointPtr joint = model->GetJoint(i);
00692         // look for it in jobs, delete joint force jobs
00693         this->clearJointForces(joint->GetName());
00694       }
00695 
00696       // clear entity from selection @todo: need to clear links if selected individually
00697       gazebo::event::Events::setSelectedEntity(req.model_name);
00698       // send delete model request
00699       gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest("entity_delete",req.model_name);
00700       this->request_pub_->Publish(*msg,true);
00701 
00702       ros::Duration model_spawn_timeout(60.0);
00703       ros::Time timeout = ros::Time::now() + model_spawn_timeout;
00704       // wait and verify that model is deleted
00705       while (true)
00706       {
00707         if (ros::Time::now() > timeout)
00708         {
00709           res.success = false;
00710           res.status_message = std::string("DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation");
00711           return false;
00712         }
00713         {
00714           //boost::recursive_mutex::scoped_lock lock(*this->world->GetMRMutex());
00715           if (!this->world->GetModel(req.model_name)) break;
00716         }
00717         ROS_DEBUG("Waiting for model deletion (%s)",req.model_name.c_str());
00718         usleep(1000);
00719       }
00720 
00721       // set result
00722       res.success = true;
00723       res.status_message = std::string("DeleteModel: successfully deleted model");
00724       return true;
00725     }
00726 
00729     bool GazeboRosApiPlugin::getModelState(gazebo_msgs::GetModelState::Request &req,gazebo_msgs::GetModelState::Response &res)
00730     {
00731       gazebo::physics::ModelPtr model = this->world->GetModel(req.model_name);
00732       gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.relative_entity_name));
00733       if (!model)
00734       {
00735         ROS_ERROR("GetModelState: model [%s] does not exist",req.model_name.c_str());
00736         res.success = false;
00737         res.status_message = "GetModelState: model does not exist";
00738         return false;
00739       }
00740       else
00741       {
00742         // get model pose
00743         gazebo::math::Pose       model_pose = model->GetWorldPose();
00744         gazebo::math::Vector3    model_pos = model_pose.pos;
00745         gazebo::math::Quaternion model_rot = model_pose.rot;
00746 
00747         // get model twist
00748         gazebo::math::Vector3 model_linear_vel  = model->GetWorldLinearVel();
00749         gazebo::math::Vector3 model_angular_vel = model->GetWorldAngularVel();
00750 
00751 
00752         if (frame)
00753         {
00754           // convert to relative pose
00755           gazebo::math::Pose frame_pose = frame->GetWorldPose();
00756           model_pos = model_pos - frame_pose.pos;
00757           model_pos = frame_pose.rot.RotateVectorReverse(model_pos);
00758           model_rot *= frame_pose.rot.GetInverse();
00759 
00760           // convert to relative rates
00761           gazebo::math::Vector3 frame_vpos = frame->GetWorldLinearVel(); // get velocity in gazebo frame
00762           gazebo::math::Vector3 frame_veul = frame->GetWorldAngularVel(); // get velocity in gazebo frame
00763           model_linear_vel = frame_pose.rot.RotateVector(model_linear_vel - frame_vpos);
00764           model_angular_vel = frame_pose.rot.RotateVector(model_angular_vel - frame_veul);
00765         }
00767         else if (req.relative_entity_name == "" || req.relative_entity_name == "world" || req.relative_entity_name == "map" || req.relative_entity_name == "/map")
00768         {
00769             ROS_DEBUG("GetModelState: relative_entity_name is empty/world/map, using inertial frame");
00770         }
00771         else
00772         {
00773           res.success = false;
00774           res.status_message = "GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
00775           return false;
00776         }
00777 
00778         // fill in response
00779         res.pose.position.x = model_pos.x;
00780         res.pose.position.y = model_pos.y;
00781         res.pose.position.z = model_pos.z;
00782         res.pose.orientation.w = model_rot.w;
00783         res.pose.orientation.x = model_rot.x;
00784         res.pose.orientation.y = model_rot.y;
00785         res.pose.orientation.z = model_rot.z;
00786 
00787         res.twist.linear.x = model_linear_vel.x;
00788         res.twist.linear.y = model_linear_vel.y;
00789         res.twist.linear.z = model_linear_vel.z;
00790         res.twist.angular.x = model_angular_vel.x;
00791         res.twist.angular.y = model_angular_vel.y;
00792         res.twist.angular.z = model_angular_vel.z;
00793 
00794         res.success = true;
00795         res.status_message = "GetModelState: got properties";
00796         return true;
00797       }
00798       return true;
00799     }
00800 
00803     bool GazeboRosApiPlugin::getModelProperties(gazebo_msgs::GetModelProperties::Request &req,gazebo_msgs::GetModelProperties::Response &res)
00804     {
00805       gazebo::physics::ModelPtr model = this->world->GetModel(req.model_name);
00806       if (!model)
00807       {
00808         ROS_ERROR("GetModelProperties: model [%s] does not exist",req.model_name.c_str());
00809         res.success = false;
00810         res.status_message = "GetModelProperties: model does not exist";
00811         return false;
00812       }
00813       else
00814       {
00815         // get model parent name
00816         gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
00817         if (parent_model) res.parent_model_name = parent_model->GetName();
00818 
00819         // get list of child bodies, geoms
00820         res.body_names.clear();
00821         res.geom_names.clear();
00822         for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
00823         {
00824           gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
00825           if (body)
00826           {
00827             res.body_names.push_back(body->GetName());
00828             // get list of geoms
00829             for (unsigned int j = 0; j < body->GetChildCount() ; j++)
00830             {
00831               gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
00832               if (geom)
00833                 res.geom_names.push_back(geom->GetName());
00834             }
00835           }
00836         }
00837 
00838         // get list of joints
00839         res.joint_names.clear();
00840         unsigned int jc = model->GetJointCount();
00841         for (unsigned int i = 0; i < jc ; i++)
00842           res.joint_names.push_back( model->GetJoint(i)->GetName() );
00843 
00844         // get children model names
00845         res.child_model_names.clear();
00846         for (unsigned int j = 0; j < model->GetChildCount(); j++)
00847         {
00848           gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
00849           if (child_model)
00850             res.child_model_names.push_back(child_model->GetName() );
00851         }
00852 
00853         // is model static
00854         res.is_static = model->IsStatic();
00855 
00856         res.success = true;
00857         res.status_message = "GetModelProperties: got properties";
00858         return true;
00859       }
00860       return true;
00861     }
00862 
00865     bool GazeboRosApiPlugin::getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,gazebo_msgs::GetWorldProperties::Response &res)
00866     {
00867       res.sim_time = this->world->GetSimTime().Double();
00868       res.model_names.clear();
00869       for (unsigned int i = 0; i < this->world->GetModelCount(); i ++)
00870         res.model_names.push_back(this->world->GetModel(i)->GetName());
00871       gzerr << "disablign rendering has not been implemented, rendering is always enabled\n";
00872       res.rendering_enabled = true; //this->world->GetRenderEngineEnabled();
00873       res.success = true;
00874       res.status_message = "GetWorldProperties: got properties";
00875       return true;
00876     }
00877 
00880     bool GazeboRosApiPlugin::getJointProperties(gazebo_msgs::GetJointProperties::Request &req,gazebo_msgs::GetJointProperties::Response &res)
00881     {
00882       gazebo::physics::JointPtr joint;
00883       for (unsigned int i = 0; i < this->world->GetModelCount(); i ++)
00884       {
00885         joint = this->world->GetModel(i)->GetJoint(req.joint_name);
00886         if (joint) break;
00887       }
00888 
00889       if (joint)
00890       {
00891         res.success = false;
00892         res.status_message = "GetJointProperties: joint not found";
00893         return false;
00894       }
00895       else
00896       {
00898         res.type = res.REVOLUTE;
00899 
00900         res.damping.clear(); // to be added to gazebo
00901         //res.damping.push_back(joint->GetDamping(0));
00902 
00903         res.position.clear(); // use GetAngle(i)
00904         res.position.push_back(joint->GetAngle(0).GetAsRadian());
00905 
00906         res.rate.clear(); // use GetVelocity(i)
00907         res.rate.push_back(joint->GetVelocity(0));
00908 
00909         res.success = true;
00910         res.status_message = "GetJointProperties: got properties";
00911         return true;
00912       }
00913     }
00914 
00917     bool GazeboRosApiPlugin::getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,gazebo_msgs::GetLinkProperties::Response &res)
00918     {
00919       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.link_name));
00920       if (body)
00921       {
00922         res.success = false;
00923         res.status_message = "GetLinkProperties: link not found, did you forget to scope the link by model name?";
00924         return false;
00925       }
00926       else
00927       {
00929         res.gravity_mode = body->GetGravityMode();
00930 
00931         res.mass = body->GetInertial()->GetMass();
00932 
00933         gazebo::physics::InertialPtr inertia = body->GetInertial();
00934         res.ixx = inertia->GetIXX();
00935         res.iyy = inertia->GetIYY();
00936         res.izz = inertia->GetIZZ();
00937         res.ixy = inertia->GetIXY();
00938         res.ixz = inertia->GetIXZ();
00939         res.iyz = inertia->GetIYZ();
00940 
00941         gazebo::math::Vector3 com = body->GetInertial()->GetCoG();
00942         res.com.position.x = com.x;
00943         res.com.position.y = com.y;
00944         res.com.position.z = com.z;
00945         res.com.orientation.x = 0; // @todo: gazebo do not support rotated inertia yet
00946         res.com.orientation.y = 0;
00947         res.com.orientation.z = 0;
00948         res.com.orientation.w = 1;
00949 
00950         res.success = true;
00951         res.status_message = "GetLinkProperties: got properties";
00952         return true;
00953       }
00954     }
00955 
00958     bool GazeboRosApiPlugin::getLinkState(gazebo_msgs::GetLinkState::Request &req,gazebo_msgs::GetLinkState::Response &res)
00959     {
00960       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.link_name));
00961       gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.reference_frame));
00962 
00963       if (body)
00964       {
00965         res.success = false;
00966         res.status_message = "GetLinkState: link not found, did you forget to scope the link by model name?";
00967         return false;
00968       }
00969 
00970       // get body pose
00971       gazebo::math::Pose body_pose = body->GetWorldPose();
00972       // Get inertial rates
00973       gazebo::math::Vector3 body_vpos = body->GetWorldLinearVel(); // get velocity in gazebo frame
00974       gazebo::math::Vector3 body_veul = body->GetWorldAngularVel(); // get velocity in gazebo frame
00975 
00976       if (frame)
00977       {
00978         // convert to relative pose
00979         gazebo::math::Pose frame_pose = frame->GetWorldPose();
00980         body_pose.pos = body_pose.pos - frame_pose.pos;
00981         body_pose.pos = frame_pose.rot.RotateVectorReverse(body_pose.pos);
00982         body_pose.rot *= frame_pose.rot.GetInverse();
00983 
00984         // convert to relative rates
00985         gazebo::math::Vector3 frame_vpos = frame->GetWorldLinearVel(); // get velocity in gazebo frame
00986         gazebo::math::Vector3 frame_veul = frame->GetWorldAngularVel(); // get velocity in gazebo frame
00987         body_vpos = frame_pose.rot.RotateVector(body_vpos - frame_vpos);
00988         body_veul = frame_pose.rot.RotateVector(body_veul - frame_veul);
00989       }
00991       else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
00992       {
00993           ROS_DEBUG("GetLinkState: reference_frame is empty/world/map, using inertial frame");
00994       }
00995       else
00996       {
00997         res.success = false;
00998         res.status_message = "GetLinkState: reference reference_frame not found, did you forget to scope the link by model name?";
00999         return false;
01000       }
01001 
01002       res.link_state.link_name = req.link_name;
01003       res.link_state.pose.position.x = body_pose.pos.x;
01004       res.link_state.pose.position.y = body_pose.pos.y;
01005       res.link_state.pose.position.z = body_pose.pos.z;
01006       res.link_state.pose.orientation.x = body_pose.rot.x;
01007       res.link_state.pose.orientation.y = body_pose.rot.y;
01008       res.link_state.pose.orientation.z = body_pose.rot.z;
01009       res.link_state.pose.orientation.w = body_pose.rot.w;
01010       res.link_state.twist.linear.x = body_vpos.x;
01011       res.link_state.twist.linear.y = body_vpos.y;
01012       res.link_state.twist.linear.z = body_vpos.z;
01013       res.link_state.twist.angular.x = body_veul.x;
01014       res.link_state.twist.angular.y = body_veul.y;
01015       res.link_state.twist.angular.z = body_veul.x;
01016       res.link_state.reference_frame = req.reference_frame;
01017 
01018       res.success = true;
01019       res.status_message = "GetLinkState: got state";
01020       return true;
01021     }
01022 
01025     bool GazeboRosApiPlugin::setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req,gazebo_msgs::SetLinkProperties::Response &res)
01026     {
01027       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.link_name));
01028       if (body)
01029       {
01030         res.success = false;
01031         res.status_message = "SetLinkProperties: link not found, did you forget to scope the link by model name?";
01032         return false;
01033       }
01034       else
01035       {
01036         gazebo::physics::InertialPtr mass = body->GetInertial();
01037         // @todo: FIXME: add inertia matrix rotation to Gazebo
01038         // mass.SetInertiaRotation(gazebo::math::Quaternionion(req.com.orientation.w,res.com.orientation.x,req.com.orientation.y req.com.orientation.z));
01039         mass->SetCoG(gazebo::math::Vector3(req.com.position.x,req.com.position.y,req.com.position.z));
01040         mass->SetInertiaMatrix(req.ixx,req.iyy,req.izz,req.ixy,req.ixz,req.iyz);
01041         mass->SetMass(req.mass);
01042         body->SetGravityMode(req.gravity_mode);
01043         // @todo: mass change unverified
01044         res.success = true;
01045         res.status_message = "SetLinkProperties: properties set";
01046         return true;
01047       }
01048     }
01049 
01052     bool GazeboRosApiPlugin::setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req,gazebo_msgs::SetPhysicsProperties::Response &res)
01053     {
01054       // pause simulation if requested
01055       bool is_paused = this->world->IsPaused();
01056       this->world->SetPaused(true);
01057 
01058       // supported updates
01059       gazebo::physics::PhysicsEnginePtr ode_pe = (this->world->GetPhysicsEngine());
01060       ode_pe->SetStepTime(req.time_step);
01061       ode_pe->SetUpdateRate(req.max_update_rate);
01062       ode_pe->SetGravity(gazebo::math::Vector3(req.gravity.x,req.gravity.y,req.gravity.z));
01063 
01064       // stuff only works in ODE right now
01065       ode_pe->SetAutoDisableFlag(req.ode_config.auto_disable_bodies);
01066       ode_pe->SetSORPGSPreconIters(req.ode_config.sor_pgs_precon_iters);
01067       ode_pe->SetSORPGSIters(req.ode_config.sor_pgs_iters);
01068       ode_pe->SetSORPGSW(req.ode_config.sor_pgs_w);
01069       ode_pe->SetWorldCFM(req.ode_config.cfm);
01070       ode_pe->SetWorldERP(req.ode_config.erp);
01071       ode_pe->SetContactSurfaceLayer(req.ode_config.contact_surface_layer);
01072       ode_pe->SetContactMaxCorrectingVel(req.ode_config.contact_max_correcting_vel);
01073       ode_pe->SetMaxContacts(req.ode_config.max_contacts);
01074 
01075       this->world->SetPaused(is_paused);
01076 
01077       res.success = true;
01078       res.status_message = "physics engine updated";
01079       return true;
01080     }
01081 
01084     bool GazeboRosApiPlugin::getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req,gazebo_msgs::GetPhysicsProperties::Response &res)
01085     {
01086       // supported updates
01087       res.time_step = this->world->GetPhysicsEngine()->GetStepTime();
01088       res.pause = this->world->IsPaused();
01089       res.max_update_rate = this->world->GetPhysicsEngine()->GetUpdateRate();
01090       gazebo::math::Vector3 gravity = this->world->GetPhysicsEngine()->GetGravity();
01091       res.gravity.x = gravity.x;
01092       res.gravity.y = gravity.y;
01093       res.gravity.z = gravity.z;
01094 
01095       // stuff only works in ODE right now
01096       res.ode_config.auto_disable_bodies = this->world->GetPhysicsEngine()->GetAutoDisableFlag();
01097       res.ode_config.sor_pgs_precon_iters = this->world->GetPhysicsEngine()->GetSORPGSPreconIters();
01098       res.ode_config.sor_pgs_iters = this->world->GetPhysicsEngine()->GetSORPGSIters();
01099       res.ode_config.sor_pgs_w = this->world->GetPhysicsEngine()->GetSORPGSW();
01100       res.ode_config.contact_surface_layer = this->world->GetPhysicsEngine()->GetContactSurfaceLayer();
01101       res.ode_config.contact_max_correcting_vel = this->world->GetPhysicsEngine()->GetContactMaxCorrectingVel();
01102       res.ode_config.cfm = this->world->GetPhysicsEngine()->GetWorldCFM();
01103       res.ode_config.erp = this->world->GetPhysicsEngine()->GetWorldERP();
01104       res.ode_config.max_contacts = this->world->GetPhysicsEngine()->GetMaxContacts();
01105 
01106       res.success = true;
01107       res.status_message = "GetPhysicsProperties: got properties";
01108       return true;
01109     }
01110 
01113     bool GazeboRosApiPlugin::setJointProperties(gazebo_msgs::SetJointProperties::Request &req,gazebo_msgs::SetJointProperties::Response &res)
01114     {
01116       gazebo::physics::JointPtr joint;
01117       for (unsigned int i = 0; i < this->world->GetModelCount(); i ++)
01118       {
01119         joint = this->world->GetModel(i)->GetJoint(req.joint_name);
01120         if (joint) break;
01121       }
01122 
01123       if (joint)
01124       {
01125         res.success = false;
01126         res.status_message = "SetJointProperties: joint not found";
01127         return false;
01128       }
01129       else
01130       {
01131         for(unsigned int i=0;i< req.ode_joint_config.damping.size();i++)
01132           joint->SetDamping(i,req.ode_joint_config.damping[i]);
01133         for(unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
01134           joint->SetAttribute(gazebo::physics::Joint::HI_STOP,i,req.ode_joint_config.hiStop[i]);
01135         for(unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
01136           joint->SetAttribute(gazebo::physics::Joint::LO_STOP,i,req.ode_joint_config.loStop[i]);
01137         for(unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
01138           joint->SetAttribute(gazebo::physics::Joint::ERP,i,req.ode_joint_config.erp[i]);
01139         for(unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
01140           joint->SetAttribute(gazebo::physics::Joint::CFM,i,req.ode_joint_config.cfm[i]);
01141         for(unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
01142           joint->SetAttribute(gazebo::physics::Joint::STOP_ERP,i,req.ode_joint_config.stop_erp[i]);
01143         for(unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
01144           joint->SetAttribute(gazebo::physics::Joint::STOP_CFM,i,req.ode_joint_config.stop_cfm[i]);
01145         for(unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
01146           joint->SetAttribute(gazebo::physics::Joint::FUDGE_FACTOR,i,req.ode_joint_config.fudge_factor[i]);
01147         for(unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
01148           joint->SetAttribute(gazebo::physics::Joint::FMAX,i,req.ode_joint_config.fmax[i]);
01149         for(unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
01150           joint->SetAttribute(gazebo::physics::Joint::VEL,i,req.ode_joint_config.vel[i]);
01151 
01152         res.success = true;
01153         res.status_message = "SetJointProperties: properties set";
01154         return true;
01155       }
01156     }
01157 
01160     bool GazeboRosApiPlugin::setModelState(gazebo_msgs::SetModelState::Request &req,gazebo_msgs::SetModelState::Response &res)
01161     {
01162       gazebo::math::Vector3 target_pos(req.model_state.pose.position.x,req.model_state.pose.position.y,req.model_state.pose.position.z);
01163       gazebo::math::Quaternion target_rot(req.model_state.pose.orientation.w,req.model_state.pose.orientation.x,req.model_state.pose.orientation.y,req.model_state.pose.orientation.z);
01164       target_rot.Normalize(); // eliminates invalid rotation (0, 0, 0, 0)
01165       gazebo::math::Pose target_pose(target_pos,target_rot);
01166       gazebo::math::Vector3 target_pos_dot(req.model_state.twist.linear.x,req.model_state.twist.linear.y,req.model_state.twist.linear.z);
01167       gazebo::math::Vector3 target_rot_dot(req.model_state.twist.angular.x,req.model_state.twist.angular.y,req.model_state.twist.angular.z);
01168 
01169       gazebo::physics::ModelPtr model = this->world->GetModel(req.model_state.model_name);
01170       if (!model)
01171       {
01172         ROS_ERROR("Updating ModelState: model [%s] does not exist",req.model_state.model_name.c_str());
01173         res.success = false;
01174         res.status_message = "SetModelState: model does not exist";
01175         return false;
01176       }
01177       else
01178       {
01179         gazebo::physics::LinkPtr relative_entity = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.model_state.reference_frame));
01180         if (relative_entity)
01181         {
01182           gazebo::math::Pose  frame_pose = relative_entity->GetWorldPose(); // - this->myBody->GetCoMPose();
01183           gazebo::math::Vector3 frame_pos = frame_pose.pos;
01184           gazebo::math::Quaternion frame_rot = frame_pose.rot;
01185 
01186           //std::cout << " debug : " << relative_entity->GetName() << " : " << frame_pose << " : " << target_pose << std::endl;
01187           //target_pose = frame_pose + target_pose; // seems buggy, use my own
01188           target_pose.pos = frame_pos + frame_rot.RotateVector(target_pos);
01189           target_pose.rot = frame_rot * target_pose.rot;
01190         }
01192         else if (req.model_state.reference_frame == "" || req.model_state.reference_frame == "world" || req.model_state.reference_frame == "map" || req.model_state.reference_frame == "/map" )
01193         {
01194           ROS_DEBUG("Updating ModelState: reference frame is empty/world/map, usig inertial frame");
01195         }
01196         else
01197         {
01198           ROS_ERROR("Updating ModelState: for model[%s], specified reference frame entity [%s] does not exist",
01199                     req.model_state.model_name.c_str(),req.model_state.reference_frame.c_str());
01200           res.success = false;
01201           res.status_message = "SetModelState: specified reference frame entity does not exist";
01202           return false;
01203         }
01204 
01205         //ROS_ERROR("target state: %f %f %f",target_pose.pos.x,target_pose.pos.y,target_pose.pos.z);
01206         bool is_paused = this->world->IsPaused();
01207         this->world->SetPaused(true);
01208         model->SetWorldPose(target_pose);
01209         this->world->SetPaused(is_paused);
01210         //gazebo::math::Pose p3d = model->GetWorldPose();
01211         //ROS_ERROR("model updated state: %f %f %f",p3d.pos.x,p3d.pos.y,p3d.pos.z);
01212 
01213         // set model velocity
01214         model->SetLinearVel(target_pos_dot);
01215         model->SetAngularVel(target_rot_dot);
01216 
01217         res.success = true;
01218         res.status_message = "SetModelState: set model state done";
01219         return true;
01220       }
01221     }
01222 
01225     void GazeboRosApiPlugin::updateModelState(const gazebo_msgs::ModelState::ConstPtr& model_state)
01226     {
01227       gazebo_msgs::SetModelState::Response res;
01228       gazebo_msgs::SetModelState::Request req;
01229       req.model_state = *model_state;
01230       /*bool success =*/ this->setModelState(req,res);
01231     }
01232 
01235     bool GazeboRosApiPlugin::applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req,gazebo_msgs::ApplyJointEffort::Response &res)
01236     {
01237       gazebo::physics::JointPtr joint;
01238       for (unsigned int i = 0; i < this->world->GetModelCount(); i ++)
01239       {
01240         joint = this->world->GetModel(i)->GetJoint(req.joint_name);
01241         if (joint)
01242         {
01243           GazeboRosApiPlugin::ForceJointJob* fjj = new GazeboRosApiPlugin::ForceJointJob;
01244           fjj->joint = joint;
01245           fjj->force = req.effort;
01246           fjj->start_time = req.start_time;
01247           if (fjj->start_time < ros::Time(this->world->GetSimTime().Double()))
01248             fjj->start_time = ros::Time(this->world->GetSimTime().Double());
01249           fjj->duration = req.duration;
01250           this->lock_.lock();
01251           this->force_joint_jobs.push_back(fjj);
01252           this->lock_.unlock();
01253 
01254           res.success = true;
01255           res.status_message = "ApplyJointEffort: effort set";
01256           return true;
01257         }
01258       }
01259 
01260       res.success = false;
01261       res.status_message = "ApplyJointEffort: joint not found";
01262       return false;
01263     }
01264 
01267     bool GazeboRosApiPlugin::resetSimulation(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01268     {
01269       this->world->Reset();
01270       return true;
01271     }
01272 
01275     bool GazeboRosApiPlugin::resetWorld(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01276     {
01277       this->world->ResetEntities(gazebo::physics::Base::MODEL);
01278       return true;
01279     }
01280 
01283     bool GazeboRosApiPlugin::pausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01284     {
01285       this->world->SetPaused(true);
01286       return true;
01287     }
01288 
01291     bool GazeboRosApiPlugin::unpausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01292     {
01293       this->world->SetPaused(false);
01294       return true;
01295     }
01296 
01299     bool GazeboRosApiPlugin::clearJointForces(gazebo_msgs::JointRequest::Request &req,gazebo_msgs::JointRequest::Response &res)
01300     {
01301       return this->clearJointForces(req.joint_name);
01302     }
01303     bool GazeboRosApiPlugin::clearJointForces(std::string joint_name)
01304     {
01305       bool search = true;
01306       this->lock_.lock();
01307       while(search)
01308       {
01309         search = false;
01310         for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=this->force_joint_jobs.begin();iter!=this->force_joint_jobs.end();iter++)
01311         {
01312           if ((*iter)->joint->GetName() == joint_name)
01313           {
01314             // found one, search through again
01315             search = true;
01316             delete (*iter);
01317             this->force_joint_jobs.erase(iter);
01318             break;
01319           }
01320         }
01321       }
01322       this->lock_.unlock();
01323       return true;
01324     }
01325 
01328     bool GazeboRosApiPlugin::clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req,gazebo_msgs::BodyRequest::Response &res)
01329     {
01330       return this->clearBodyWrenches(req.body_name);
01331     }
01332     bool GazeboRosApiPlugin::clearBodyWrenches(std::string body_name)
01333     {
01334       bool search = true;
01335       this->lock_.lock();
01336       while(search)
01337       {
01338         search = false;
01339         for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=this->wrench_body_jobs.begin();iter!=this->wrench_body_jobs.end();iter++)
01340         {
01341           //ROS_ERROR("search %s %s",(*iter)->body->GetScopedName().c_str(), body_name.c_str());
01342           if ((*iter)->body->GetScopedName() == body_name)
01343           {
01344             // found one, search through again
01345             search = true;
01346             delete (*iter);
01347             this->wrench_body_jobs.erase(iter);
01348             break;
01349           }
01350         }
01351       }
01352       this->lock_.unlock();
01353       return true;
01354     }
01355 
01360     bool GazeboRosApiPlugin::setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req,gazebo_msgs::SetModelConfiguration::Response &res)
01361     {
01362       std::string gazebo_model_name = req.model_name;
01363 
01364       // search for model with name
01365       gazebo::physics::ModelPtr gazebo_model = this->world->GetModel(req.model_name);
01366       if (!gazebo_model)
01367       {
01368         ROS_ERROR("SetModelConfiguration: model [%s] does not exist",gazebo_model_name.c_str());
01369         res.success = false;
01370         res.status_message = "SetModelConfiguration: model does not exist";
01371         return false;
01372       }
01373 
01374       if (req.joint_names.size() == req.joint_positions.size())
01375       {
01376         std::map<std::string, double> joint_position_map;
01377         for (unsigned int i = 0; i < req.joint_names.size(); i++)
01378         {
01379           joint_position_map[req.joint_names[i]] = req.joint_positions[i];
01380         }
01381 
01382         // make the service call to pause gazebo
01383         bool is_paused = this->world->IsPaused();
01384         if (!is_paused) this->world->SetPaused(true);
01385 
01386         gazebo_model->SetJointPositions(joint_position_map);
01387 
01388         // resume paused state before this call
01389         this->world->SetPaused(is_paused);
01390 
01391         res.success = true;
01392         res.status_message = "SetModelConfiguration: success";
01393         return true;
01394       }
01395       else
01396       {
01397         res.success = false;
01398         res.status_message = "SetModelConfiguration: joint name and position list have different lengths";
01399         return false;
01400       }
01401     }
01402 
01405     bool GazeboRosApiPlugin::setLinkState(gazebo_msgs::SetLinkState::Request &req,gazebo_msgs::SetLinkState::Response &res)
01406     {
01407       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.link_state.link_name));
01408       gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.link_state.reference_frame));
01409       if (!body)
01410       {
01411         ROS_ERROR("Updating LinkState: link [%s] does not exist",req.link_state.link_name.c_str());
01412         res.success = false;
01413         res.status_message = "SetLinkState: link does not exist";
01414         return false;
01415       }
01416 
01418       // get reference frame (body/model(link)) pose and
01419       // transform target pose to absolute world frame
01420       gazebo::math::Vector3 target_pos(req.link_state.pose.position.x,req.link_state.pose.position.y,req.link_state.pose.position.z);
01421       gazebo::math::Quaternion target_rot(req.link_state.pose.orientation.w,req.link_state.pose.orientation.x,req.link_state.pose.orientation.y,req.link_state.pose.orientation.z);
01422       gazebo::math::Pose target_pose(target_pos,target_rot);
01423       gazebo::math::Vector3 target_linear_vel(req.link_state.twist.linear.x,req.link_state.twist.linear.y,req.link_state.twist.linear.z);
01424       gazebo::math::Vector3 target_angular_vel(req.link_state.twist.angular.x,req.link_state.twist.angular.y,req.link_state.twist.angular.z);
01425 
01426       if (frame)
01427       {
01428         gazebo::math::Pose  frame_pose = frame->GetWorldPose(); // - this->myBody->GetCoMPose();
01429         gazebo::math::Vector3 frame_pos = frame_pose.pos;
01430         gazebo::math::Quaternion frame_rot = frame_pose.rot;
01431 
01432         //std::cout << " debug : " << frame->GetName() << " : " << frame_pose << " : " << target_pose << std::endl;
01433         //target_pose = frame_pose + target_pose; // seems buggy, use my own
01434         target_pose.pos = frame_pos + frame_rot.RotateVector(target_pos);
01435         target_pose.rot = frame_rot * target_pose.rot;
01436 
01437         gazebo::math::Vector3 frame_linear_vel = frame->GetWorldLinearVel();
01438         gazebo::math::Vector3 frame_angular_vel = frame->GetWorldAngularVel();
01439         target_linear_vel -= frame_linear_vel;
01440         target_angular_vel -= frame_angular_vel;
01441       }
01442       else if (req.link_state.reference_frame == "" || req.link_state.reference_frame == "world" || req.link_state.reference_frame == "map" || req.link_state.reference_frame == "/map")
01443       {
01444         ROS_INFO("Updating LinkState: reference_frame is empty/world/map, using inertial frame");
01445       }
01446       else
01447       {
01448         ROS_ERROR("Updating LinkState: reference_frame is not a valid link name");
01449         res.success = false;
01450         res.status_message = "SetLinkState: failed";
01451         return false;
01452       }
01453 
01454       //std::cout << " debug : " << target_pose << std::endl;
01455       //boost::recursive_mutex::scoped_lock lock(*this->world->GetMRMutex());
01456 
01457       bool is_paused = this->world->IsPaused();
01458       if (!is_paused) this->world->SetPaused(true);
01459       body->SetWorldPose(target_pose);
01460       this->world->SetPaused(is_paused);
01461 
01462       // set body velocity to desired twist
01463       body->SetLinearVel(target_linear_vel);
01464       body->SetAngularVel(target_angular_vel);
01465 
01466       res.success = true;
01467       res.status_message = "SetLinkState: success";
01468       return true;
01469     }
01470 
01473     void GazeboRosApiPlugin::updateLinkState(const gazebo_msgs::LinkState::ConstPtr& link_state)
01474     {
01475       gazebo_msgs::SetLinkState::Request req;
01476       gazebo_msgs::SetLinkState::Response res;
01477       req.link_state = *link_state;
01478       /*bool success = */ this->setLinkState(req,res);
01479     }
01480 
01481 
01485     void GazeboRosApiPlugin::transformWrench( gazebo::math::Vector3 &target_force, gazebo::math::Vector3 &target_torque,
01486                                gazebo::math::Vector3 reference_force, gazebo::math::Vector3 reference_torque,
01487                                gazebo::math::Pose target_to_reference )
01488     {
01489       // rotate force into target frame
01490       target_force = target_to_reference.rot.RotateVector(reference_force);
01491       // rotate torque into target frame
01492       target_torque = target_to_reference.rot.RotateVector(reference_torque);
01493 
01494       // target force is the refence force rotated by the target->reference transform
01495       target_force = target_force;
01496       target_torque = target_torque + target_to_reference.pos.GetCrossProd(target_force);
01497     }
01498 
01501     bool GazeboRosApiPlugin::applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req,gazebo_msgs::ApplyBodyWrench::Response &res)
01502     {
01503       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.body_name));
01504       gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(this->world->GetEntity(req.reference_frame));
01505       if (!body)
01506       {
01507         ROS_ERROR("ApplyBodyWrench: body [%s] does not exist",req.body_name.c_str());
01508         res.success = false;
01509         res.status_message = "ApplyBodyWrench: body does not exist";
01510         return false;
01511       }
01512 
01513       // target wrench
01514       gazebo::math::Vector3 reference_force(req.wrench.force.x,req.wrench.force.y,req.wrench.force.z);
01515       gazebo::math::Vector3 reference_torque(req.wrench.torque.x,req.wrench.torque.y,req.wrench.torque.z);
01516       gazebo::math::Vector3 reference_point(req.reference_point.x,req.reference_point.y,req.reference_point.z);
01517 
01518       gazebo::math::Vector3 target_force;
01519       gazebo::math::Vector3 target_torque;
01520 
01523       reference_torque = reference_torque + reference_point.GetCrossProd(reference_force);
01524 
01526       if (frame)
01527       {
01528         // get reference frame (body/model(body)) pose and
01529         // transform target pose to absolute world frame
01530         // @todo: need to modify wrench (target force and torque by frame)
01531         //        transform wrench from reference_point in reference_frame
01532         //        into the reference frame of the body
01533         //        first, translate by reference point to the body frame
01534         gazebo::math::Pose target_to_reference = frame->GetWorldPose() - body->GetWorldPose();
01535         ROS_DEBUG("reference frame for applied wrench: [%f %f %f, %f %f %f]-[%f %f %f, %f %f %f]=[%f %f %f, %f %f %f]",
01536                    body->GetWorldPose().pos.x,
01537                    body->GetWorldPose().pos.y,
01538                    body->GetWorldPose().pos.z,
01539                    body->GetWorldPose().rot.GetAsEuler().x,
01540                    body->GetWorldPose().rot.GetAsEuler().y,
01541                    body->GetWorldPose().rot.GetAsEuler().z,
01542                    frame->GetWorldPose().pos.x,
01543                    frame->GetWorldPose().pos.y,
01544                    frame->GetWorldPose().pos.z,
01545                    frame->GetWorldPose().rot.GetAsEuler().x,
01546                    frame->GetWorldPose().rot.GetAsEuler().y,
01547                    frame->GetWorldPose().rot.GetAsEuler().z,
01548                    target_to_reference.pos.x,
01549                    target_to_reference.pos.y,
01550                    target_to_reference.pos.z,
01551                    target_to_reference.rot.GetAsEuler().x,
01552                    target_to_reference.rot.GetAsEuler().y,
01553                    target_to_reference.rot.GetAsEuler().z
01554                  );
01555         this->transformWrench(target_force, target_torque, reference_force, reference_torque, target_to_reference);
01556         ROS_ERROR("wrench defined as [%s]:[%f %f %f, %f %f %f] --> applied as [%s]:[%f %f %f, %f %f %f]",
01557                    frame->GetName().c_str(),
01558                    reference_force.x,
01559                    reference_force.y,
01560                    reference_force.z,
01561                    reference_torque.x,
01562                    reference_torque.y,
01563                    reference_torque.z,
01564                    body->GetName().c_str(),
01565                    target_force.x,
01566                    target_force.y,
01567                    target_force.z,
01568                    target_torque.x,
01569                    target_torque.y,
01570                    target_torque.z
01571                  );
01572 
01573       }
01574       else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
01575       {
01576         ROS_INFO("ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame");
01577         // FIXME: transfer to inertial frame
01578         gazebo::math::Pose target_to_reference = body->GetWorldPose();
01579         target_force = reference_force;
01580         target_torque = reference_torque;
01581 
01582       }
01583       else
01584       {
01585         ROS_ERROR("ApplyBodyWrench: reference_frame is not a valid link name");
01586         res.success = false;
01587         res.status_message = "ApplyBodyWrench: reference_frame not found";
01588         return false;
01589       }
01590 
01591       // apply wrench
01592       // schedule a job to do below at appropriate times:
01593       // body->SetForce(force)
01594       // body->SetTorque(torque)
01595       GazeboRosApiPlugin::WrenchBodyJob* wej = new GazeboRosApiPlugin::WrenchBodyJob;
01596       wej->body = body;
01597       wej->force = target_force;
01598       wej->torque = target_torque;
01599       wej->start_time = req.start_time;
01600       if (wej->start_time < ros::Time(this->world->GetSimTime().Double()))
01601         wej->start_time = ros::Time(this->world->GetSimTime().Double());
01602       wej->duration = req.duration;
01603       this->lock_.lock();
01604       this->wrench_body_jobs.push_back(wej);
01605       this->lock_.unlock();
01606 
01607       res.success = true;
01608       res.status_message = "";
01609       return true;
01610     }
01611 
01612 
01613     void GazeboRosApiPlugin::spin()
01614     {
01615       // todo: make a wait loop that does not provide extra ros::spin()
01616       ros::Rate r(10);
01617       while(ros::ok())
01618       {
01619         ros::spinOnce();
01620         r.sleep();
01621       }
01622     }
01623 
01625     void GazeboRosApiPlugin::SetupTransform(btTransform &transform, urdf::Pose pose)
01626     {
01627         btMatrix3x3 mat;
01628         mat.setRotation(btQuaternion(pose.rotation.x,pose.rotation.y,pose.rotation.z,pose.rotation.w));
01629         transform = btTransform(mat,btVector3(pose.position.x,pose.position.y,pose.position.z));
01630     }
01631     void GazeboRosApiPlugin::SetupTransform(btTransform &transform, geometry_msgs::Pose pose)
01632     {
01633         btMatrix3x3 mat;
01634         mat.setRotation(btQuaternion(pose.orientation.x,pose.orientation.y,pose.orientation.z,pose.orientation.w));
01635         transform = btTransform(mat,btVector3(pose.position.x,pose.position.y,pose.position.z));
01636     }
01637 
01639     bool GazeboRosApiPlugin::IsURDF(std::string model_xml)
01640     {
01641       TiXmlDocument doc_in;
01642       doc_in.Parse(model_xml.c_str());
01643       if (doc_in.FirstChild("robot"))
01644         return true;
01645       else
01646         return false;
01647     }
01648     bool GazeboRosApiPlugin::IsGazeboModelXML(std::string model_xml)
01649     {
01650       // FIXME: very crude check
01651       TiXmlDocument doc_in;
01652       doc_in.Parse(model_xml.c_str());
01653       if (doc_in.FirstChild("model:physical")) // old gazebo xml
01654         return true;
01655       else
01656         return false;
01657     }
01658     bool GazeboRosApiPlugin::IsSDF(std::string model_xml)
01659     {
01660       // FIXME: very crude check
01661       TiXmlDocument doc_in;
01662       doc_in.Parse(model_xml.c_str());
01663       if (doc_in.FirstChild("gazebo")) // sdf
01664         return true;
01665       else
01666         return false;
01667     }
01668 
01671     void GazeboRosApiPlugin::wrenchBodySchedulerSlot()
01672     {
01673       // MDMutex locks in case model is getting deleted, don't have to do this if we delete jobs first
01674       // boost::recursive_mutex::scoped_lock lock(*this->world->GetMDMutex());
01675       this->lock_.lock();
01676       for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=this->wrench_body_jobs.begin();iter!=this->wrench_body_jobs.end();)
01677       {
01678         // check times and apply wrench if necessary
01679         if (ros::Time(this->world->GetSimTime().Double()) >= (*iter)->start_time)
01680           if (ros::Time(this->world->GetSimTime().Double()) <= (*iter)->start_time+(*iter)->duration ||
01681               (*iter)->duration.toSec() < 0.0)
01682           {
01683             if ((*iter)->body) // if body exists
01684             {
01685               (*iter)->body->SetForce((*iter)->force);
01686               (*iter)->body->SetTorque((*iter)->torque);
01687             }
01688             else
01689               (*iter)->duration.fromSec(0.0); // mark for delete
01690           }
01691 
01692         if (ros::Time(this->world->GetSimTime().Double()) > (*iter)->start_time+(*iter)->duration &&
01693             (*iter)->duration.toSec() >= 0.0)
01694         {
01695           // remove from queue once expires
01696           delete (*iter);
01697           this->wrench_body_jobs.erase(iter);
01698         }
01699         else
01700           iter++;
01701       }
01702       this->lock_.unlock();
01703     }
01704 
01707     void GazeboRosApiPlugin::forceJointSchedulerSlot()
01708     {
01709       // MDMutex locks in case model is getting deleted, don't have to do this if we delete jobs first
01710       // boost::recursive_mutex::scoped_lock lock(*this->world->GetMDMutex());
01711       this->lock_.lock();
01712       for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=this->force_joint_jobs.begin();iter!=this->force_joint_jobs.end();)
01713       {
01714         // check times and apply force if necessary
01715         if (ros::Time(this->world->GetSimTime().Double()) >= (*iter)->start_time)
01716           if (ros::Time(this->world->GetSimTime().Double()) <= (*iter)->start_time+(*iter)->duration ||
01717               (*iter)->duration.toSec() < 0.0)
01718             {
01719               if ((*iter)->joint) // if joint exists
01720                 (*iter)->joint->SetForce(0,(*iter)->force);
01721               else
01722                 (*iter)->duration.fromSec(0.0); // mark for delete
01723             }
01724 
01725         if (ros::Time(this->world->GetSimTime().Double()) > (*iter)->start_time+(*iter)->duration &&
01726             (*iter)->duration.toSec() >= 0.0)
01727         {
01728           // remove from queue once expires
01729           this->force_joint_jobs.erase(iter);
01730         }
01731         else
01732           iter++;
01733       }
01734       this->lock_.unlock();
01735     }
01736 
01739     void GazeboRosApiPlugin::publishSimTime(const boost::shared_ptr<gazebo::msgs::WorldStatistics const> &msg)
01740     {
01741       ROS_ERROR("CLOCK2");
01742       gazebo::common::Time currentTime = gazebo::msgs::Convert( msg->sim_time() );
01743       rosgraph_msgs::Clock ros_time_;
01744       ros_time_.clock.fromSec(currentTime.Double());
01745       //  publish time to ros
01746       this->pub_clock_.publish(ros_time_);
01747     }
01748     void GazeboRosApiPlugin::publishSimTime()
01749     {
01750       gazebo::common::Time currentTime = this->world->GetSimTime();
01751       rosgraph_msgs::Clock ros_time_;
01752       ros_time_.clock.fromSec(currentTime.Double());
01753       //  publish time to ros
01754       this->pub_clock_.publish(ros_time_);
01755     }
01756 
01757 
01760     void GazeboRosApiPlugin::publishLinkStates()
01761     {
01762       gazebo_msgs::LinkStates link_states;
01763 
01764       // fill link_states
01765       for (unsigned int i = 0; i < this->world->GetModelCount(); i ++)
01766       {
01767         gazebo::physics::ModelPtr model = this->world->GetModel(i);
01768 
01769         for (unsigned int j = 0 ; j < model->GetChildCount(); j ++)
01770         {
01771           gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(j));
01772 
01773           if (body)
01774           {
01775             link_states.name.push_back(body->GetScopedName());
01776             geometry_msgs::Pose pose;
01777             gazebo::math::Pose  body_pose = body->GetWorldPose(); // - this->myBody->GetCoMPose();
01778             gazebo::math::Vector3 pos = body_pose.pos;
01779             gazebo::math::Quaternion rot = body_pose.rot;
01780             pose.position.x = pos.x;
01781             pose.position.y = pos.y;
01782             pose.position.z = pos.z;
01783             pose.orientation.w = rot.w;
01784             pose.orientation.x = rot.x;
01785             pose.orientation.y = rot.y;
01786             pose.orientation.z = rot.z;
01787             link_states.pose.push_back(pose);
01788             gazebo::math::Vector3 linear_vel  = body->GetWorldLinearVel();
01789             gazebo::math::Vector3 angular_vel = body->GetWorldAngularVel();
01790             geometry_msgs::Twist twist;
01791             twist.linear.x = linear_vel.x;
01792             twist.linear.y = linear_vel.y;
01793             twist.linear.z = linear_vel.z;
01794             twist.angular.x = angular_vel.x;
01795             twist.angular.y = angular_vel.y;
01796             twist.angular.z = angular_vel.z;
01797             link_states.twist.push_back(twist);
01798           }
01799         }
01800       }
01801 
01802       this->pub_link_states_.publish(link_states);
01803     }
01804 
01807     void GazeboRosApiPlugin::publishModelStates()
01808     {
01809       gazebo_msgs::ModelStates model_states;
01810 
01811       // fill model_states
01812       for (unsigned int i = 0; i < this->world->GetModelCount(); i ++)
01813       {
01814         gazebo::physics::ModelPtr model = this->world->GetModel(i);
01815         model_states.name.push_back(model->GetName());
01816         geometry_msgs::Pose pose;
01817         gazebo::math::Pose  model_pose = model->GetWorldPose(); // - this->myBody->GetCoMPose();
01818         gazebo::math::Vector3 pos = model_pose.pos;
01819         gazebo::math::Quaternion rot = model_pose.rot;
01820         pose.position.x = pos.x;
01821         pose.position.y = pos.y;
01822         pose.position.z = pos.z;
01823         pose.orientation.w = rot.w;
01824         pose.orientation.x = rot.x;
01825         pose.orientation.y = rot.y;
01826         pose.orientation.z = rot.z;
01827         model_states.pose.push_back(pose);
01828         gazebo::math::Vector3 linear_vel  = model->GetWorldLinearVel();
01829         gazebo::math::Vector3 angular_vel = model->GetWorldAngularVel();
01830         geometry_msgs::Twist twist;
01831         twist.linear.x = linear_vel.x;
01832         twist.linear.y = linear_vel.y;
01833         twist.linear.z = linear_vel.z;
01834         twist.angular.x = angular_vel.x;
01835         twist.angular.y = angular_vel.y;
01836         twist.angular.z = angular_vel.z;
01837         model_states.twist.push_back(twist);
01838       }
01839       this->pub_model_states_.publish(model_states);
01840     }
01841 
01842     void GazeboRosApiPlugin::PhysicsReconfigureCallback(gazebo::PhysicsConfig &config, uint32_t level)
01843     {
01844       if (!physics_reconfigure_initialized_)
01845       {
01846         gazebo_msgs::GetPhysicsProperties srv;
01847         this->physics_reconfigure_get_client_.call(srv);
01848 
01849         config.time_step                   = srv.response.time_step;
01850         config.max_update_rate             = srv.response.max_update_rate;
01851         config.gravity_x                   = srv.response.gravity.x;
01852         config.gravity_y                   = srv.response.gravity.y;
01853         config.gravity_z                   = srv.response.gravity.z;
01854         config.auto_disable_bodies         = srv.response.ode_config.auto_disable_bodies;
01855         config.sor_pgs_precon_iters        = srv.response.ode_config.sor_pgs_precon_iters;
01856         config.sor_pgs_iters               = srv.response.ode_config.sor_pgs_iters;
01857         config.sor_pgs_rms_error_tol       = srv.response.ode_config.sor_pgs_rms_error_tol;
01858         config.sor_pgs_w                   = srv.response.ode_config.sor_pgs_w;
01859         config.contact_surface_layer       = srv.response.ode_config.contact_surface_layer;
01860         config.contact_max_correcting_vel  = srv.response.ode_config.contact_max_correcting_vel;
01861         config.cfm                         = srv.response.ode_config.cfm;
01862         config.erp                         = srv.response.ode_config.erp;
01863         config.max_contacts                = srv.response.ode_config.max_contacts;
01864         physics_reconfigure_initialized_ = true;
01865       }
01866       else
01867       {
01868         bool changed = false;
01869         gazebo_msgs::GetPhysicsProperties srv;
01870         this->physics_reconfigure_get_client_.call(srv);
01871 
01872         // check for changes
01873         if (config.time_step                      != srv.response.time_step)                                 changed = true;
01874         if (config.max_update_rate                != srv.response.max_update_rate)                           changed = true;
01875         if (config.gravity_x                      != srv.response.gravity.x)                                 changed = true;
01876         if (config.gravity_y                      != srv.response.gravity.y)                                 changed = true;
01877         if (config.gravity_z                      != srv.response.gravity.z)                                 changed = true;
01878         if (config.auto_disable_bodies            != srv.response.ode_config.auto_disable_bodies)            changed = true;
01879         if ((uint32_t)config.sor_pgs_precon_iters != srv.response.ode_config.sor_pgs_precon_iters)           changed = true;
01880         if ((uint32_t)config.sor_pgs_iters        != srv.response.ode_config.sor_pgs_iters)                  changed = true;
01881         if (config.sor_pgs_rms_error_tol          != srv.response.ode_config.sor_pgs_rms_error_tol)          changed = true;
01882         if (config.sor_pgs_w                      != srv.response.ode_config.sor_pgs_w)                      changed = true;
01883         if (config.contact_surface_layer          != srv.response.ode_config.contact_surface_layer)          changed = true;
01884         if (config.contact_max_correcting_vel     != srv.response.ode_config.contact_max_correcting_vel)     changed = true;
01885         if (config.cfm                            != srv.response.ode_config.cfm)                            changed = true;
01886         if (config.erp                            != srv.response.ode_config.erp)                            changed = true;
01887         if ((uint32_t)config.max_contacts         != srv.response.ode_config.max_contacts)                   changed = true;
01888 
01889         if (changed)
01890         {
01891           // pause simulation if requested
01892           gazebo_msgs::SetPhysicsProperties srv;
01893           srv.request.time_step                             = config.time_step                   ;
01894           srv.request.max_update_rate                       = config.max_update_rate             ;
01895           srv.request.gravity.x                             = config.gravity_x                   ;
01896           srv.request.gravity.y                             = config.gravity_y                   ;
01897           srv.request.gravity.z                             = config.gravity_z                   ;
01898           srv.request.ode_config.auto_disable_bodies        = config.auto_disable_bodies         ;
01899           srv.request.ode_config.sor_pgs_precon_iters       = config.sor_pgs_precon_iters        ;
01900           srv.request.ode_config.sor_pgs_iters              = config.sor_pgs_iters               ;
01901           srv.request.ode_config.sor_pgs_rms_error_tol      = config.sor_pgs_rms_error_tol       ;
01902           srv.request.ode_config.sor_pgs_w                  = config.sor_pgs_w                   ;
01903           srv.request.ode_config.contact_surface_layer      = config.contact_surface_layer       ;
01904           srv.request.ode_config.contact_max_correcting_vel = config.contact_max_correcting_vel  ;
01905           srv.request.ode_config.cfm                        = config.cfm                         ;
01906           srv.request.ode_config.erp                        = config.erp                         ;
01907           srv.request.ode_config.max_contacts               = config.max_contacts                ;
01908           this->physics_reconfigure_set_client_.call(srv);
01909           ROS_INFO("physics dynamics reconfigure update complete");
01910         }
01911         ROS_INFO("physics dynamics reconfigure complete");
01912       }
01913     }
01914 
01915     void GazeboRosApiPlugin::PhysicsReconfigureNode()
01916     {
01917       ros::NodeHandle node_handle;
01918       this->physics_reconfigure_set_client_ = node_handle.serviceClient<gazebo_msgs::SetPhysicsProperties>("/gazebo/set_physics_properties");
01919       this->physics_reconfigure_get_client_ = node_handle.serviceClient<gazebo_msgs::GetPhysicsProperties>("/gazebo/get_physics_properties");
01920       this->physics_reconfigure_set_client_.waitForExistence();
01921       this->physics_reconfigure_get_client_.waitForExistence();
01922 
01923       // for dynamic reconfigure physics
01924       // for dynamic_reconfigure
01925       dynamic_reconfigure::Server<gazebo::PhysicsConfig> physics_reconfigure_srv;
01926       dynamic_reconfigure::Server<gazebo::PhysicsConfig>::CallbackType physics_reconfigure_f;
01927 
01928       physics_reconfigure_f = boost::bind(&GazeboRosApiPlugin::PhysicsReconfigureCallback, this, _1, _2);
01929       physics_reconfigure_srv.setCallback(physics_reconfigure_f);
01930 
01931       ROS_INFO("Starting to spin physics dynamic reconfigure node...");
01932       ros::Rate r(10);
01933       while(ros::ok())
01934       {
01935         ros::spinOnce();
01936         r.sleep();
01937       }
01938     }
01939 
01940 // Register this plugin with the simulator
01941 GZ_REGISTER_SYSTEM_PLUGIN(GazeboRosApiPlugin)
01942 }
01943 


gazebo
Author(s): Nate Koenig, Andrew Howard, with contributions from many others. See web page for a full credits llist.
autogenerated on Sun Jan 5 2014 11:34:52