gazebo_ros_api_plugin.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2013 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 /* Desc: External interfaces for Gazebo
00019  * Author: Nate Koenig, John Hsu, Dave Coleman
00020  * Date: Jun 10 2013
00021  */
00022 
00023 #include <gazebo/common/Events.hh>
00024 #include <gazebo/gazebo_config.h>
00025 #include <gazebo_ros/gazebo_ros_api_plugin.h>
00026 
00027 namespace gazebo
00028 {
00029 
00030 GazeboRosApiPlugin::GazeboRosApiPlugin() :
00031   physics_reconfigure_initialized_(false),
00032   world_created_(false),
00033   stop_(false),
00034   plugin_loaded_(false),
00035   pub_link_states_connection_count_(0),
00036   pub_model_states_connection_count_(0),
00037   pub_clock_frequency_(0)
00038 {
00039   robot_namespace_.clear();
00040 }
00041 
00042 GazeboRosApiPlugin::~GazeboRosApiPlugin()
00043 {
00044   ROS_DEBUG_STREAM_NAMED("api_plugin","GazeboRosApiPlugin Deconstructor start");
00045 
00046   // Unload the sigint event
00047   gazebo::event::Events::DisconnectSigInt(sigint_event_);
00048   ROS_DEBUG_STREAM_NAMED("api_plugin","After sigint_event unload");
00049 
00050   // Don't attempt to unload this plugin if it was never loaded in the Load() function
00051   if(!plugin_loaded_)
00052   {
00053     ROS_DEBUG_STREAM_NAMED("api_plugin","Deconstructor skipped because never loaded");
00054     return;
00055   }
00056 
00057   // Disconnect slots
00058   gazebo::event::Events::DisconnectWorldCreated(load_gazebo_ros_api_plugin_event_);
00059   gazebo::event::Events::DisconnectWorldUpdateBegin(wrench_update_event_);
00060   gazebo::event::Events::DisconnectWorldUpdateBegin(force_update_event_);
00061   gazebo::event::Events::DisconnectWorldUpdateBegin(time_update_event_);
00062   ROS_DEBUG_STREAM_NAMED("api_plugin","Slots disconnected");
00063 
00064   if (pub_link_states_connection_count_ > 0) // disconnect if there are subscribers on exit
00065     gazebo::event::Events::DisconnectWorldUpdateBegin(pub_link_states_event_);
00066   if (pub_model_states_connection_count_ > 0) // disconnect if there are subscribers on exit
00067     gazebo::event::Events::DisconnectWorldUpdateBegin(pub_model_states_event_);
00068   ROS_DEBUG_STREAM_NAMED("api_plugin","Disconnected World Updates");
00069 
00070   // Stop the multi threaded ROS spinner
00071   async_ros_spin_->stop();
00072   ROS_DEBUG_STREAM_NAMED("api_plugin","Async ROS Spin Stopped");
00073 
00074   // Shutdown the ROS node
00075   nh_->shutdown();
00076   ROS_DEBUG_STREAM_NAMED("api_plugin","Node Handle Shutdown");
00077 
00078   // Shutdown ROS queue
00079   gazebo_callback_queue_thread_->join();
00080   ROS_DEBUG_STREAM_NAMED("api_plugin","Callback Queue Joined");
00081 
00082   // Physics Dynamic Reconfigure
00083   physics_reconfigure_thread_->join();
00084   ROS_DEBUG_STREAM_NAMED("api_plugin","Physics reconfigure joined");
00085 
00086   // Delete Force and Wrench Jobs
00087   lock_.lock();
00088   for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();)
00089   {
00090     delete (*iter);
00091     iter = force_joint_jobs_.erase(iter);
00092   }
00093   force_joint_jobs_.clear();
00094   ROS_DEBUG_STREAM_NAMED("api_plugin","ForceJointJobs deleted");
00095   for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();)
00096   {
00097     delete (*iter);
00098     iter = wrench_body_jobs_.erase(iter);
00099   }
00100   wrench_body_jobs_.clear();
00101   lock_.unlock();
00102   ROS_DEBUG_STREAM_NAMED("api_plugin","WrenchBodyJobs deleted");
00103 
00104   ROS_DEBUG_STREAM_NAMED("api_plugin","Unloaded");
00105 }
00106 
00107 void GazeboRosApiPlugin::shutdownSignal()
00108 {
00109   ROS_DEBUG_STREAM_NAMED("api_plugin","shutdownSignal() recieved");
00110   stop_ = true;
00111 }
00112 
00113 void GazeboRosApiPlugin::Load(int argc, char** argv)
00114 {
00115   ROS_DEBUG_STREAM_NAMED("api_plugin","Load");
00116 
00117   // connect to sigint event
00118   sigint_event_ = gazebo::event::Events::ConnectSigInt(boost::bind(&GazeboRosApiPlugin::shutdownSignal,this));
00119 
00120   // setup ros related
00121   if (!ros::isInitialized())
00122     ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler);
00123   else
00124     ROS_ERROR("Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
00125 
00126   // check if the ros master is available - required
00127   while(!ros::master::check())
00128   {
00129     ROS_WARN_STREAM_NAMED("api_plugin","No ROS master - start roscore to continue...");
00130     // wait 0.5 second
00131     usleep(500*1000); // can't use ROS Time here b/c node handle is not yet initialized
00132 
00133     if(stop_)
00134     {
00135       ROS_WARN_STREAM_NAMED("api_plugin","Canceled loading Gazebo ROS API plugin by sigint event");
00136       return;
00137     }
00138   }
00139 
00140   nh_.reset(new ros::NodeHandle("~")); // advertise topics and services in this node's namespace
00141 
00142   // Built-in multi-threaded ROS spinning
00143   async_ros_spin_.reset(new ros::AsyncSpinner(0)); // will use a thread for each CPU core
00144   async_ros_spin_->start();
00145 
00147   gazebo_callback_queue_thread_.reset(new boost::thread( &GazeboRosApiPlugin::gazeboQueueThread, this) );
00148 
00150   physics_reconfigure_thread_.reset(new boost::thread(boost::bind(&GazeboRosApiPlugin::physicsReconfigureThread, this)));
00151 
00152   // below needs the world to be created first
00153   load_gazebo_ros_api_plugin_event_ = gazebo::event::Events::ConnectWorldCreated(boost::bind(&GazeboRosApiPlugin::loadGazeboRosApiPlugin,this,_1));
00154 
00155   plugin_loaded_ = true;
00156   ROS_INFO("Finished loading Gazebo ROS API Plugin.");
00157 }
00158 
00159 void GazeboRosApiPlugin::loadGazeboRosApiPlugin(std::string world_name)
00160 {
00161   // make sure things are only called once
00162   lock_.lock();
00163   if (world_created_)
00164   {
00165     lock_.unlock();
00166     return;
00167   }
00168 
00169   // set flag to true and load this plugin
00170   world_created_ = true;
00171   lock_.unlock();
00172 
00173   world_ = gazebo::physics::get_world(world_name);
00174   if (!world_)
00175   {
00176     //ROS_ERROR("world name: [%s]",world->GetName().c_str());
00177     // connect helper function to signal for scheduling torque/forces, etc
00178     ROS_FATAL("cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
00179     return;
00180   }
00181 
00182   gazebonode_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
00183   gazebonode_->Init(world_name);
00184   //stat_sub_ = gazebonode_->Subscribe("~/world_stats", &GazeboRosApiPlugin::publishSimTime, this); // TODO: does not work in server plugin?
00185   factory_pub_ = gazebonode_->Advertise<gazebo::msgs::Factory>("~/factory");
00186   request_pub_ = gazebonode_->Advertise<gazebo::msgs::Request>("~/request");
00187   response_sub_ = gazebonode_->Subscribe("~/response",&GazeboRosApiPlugin::onResponse, this);
00188 
00189   // reset topic connection counts
00190   pub_link_states_connection_count_ = 0;
00191   pub_model_states_connection_count_ = 0;
00192 
00194   advertiseServices();
00195 
00196   // hooks for applying forces, publishing simtime on /clock
00197   wrench_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::wrenchBodySchedulerSlot,this));
00198   force_update_event_  = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::forceJointSchedulerSlot,this));
00199   time_update_event_   = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishSimTime,this));
00200 }
00201 
00202 void GazeboRosApiPlugin::onResponse(ConstResponsePtr &response)
00203 {
00204 
00205 }
00206 
00207 void GazeboRosApiPlugin::gazeboQueueThread()
00208 {
00209   static const double timeout = 0.001;
00210   while (nh_->ok())
00211   {
00212     gazebo_queue_.callAvailable(ros::WallDuration(timeout));
00213   }
00214 }
00215 
00216 void GazeboRosApiPlugin::advertiseServices()
00217 {
00218   // publish clock for simulated ros time
00219   pub_clock_ = nh_->advertise<rosgraph_msgs::Clock>("/clock",10);
00220 
00221   // Advertise spawn services on the custom queue - DEPRECATED IN HYDRO
00222   std::string spawn_gazebo_model_service_name("spawn_gazebo_model");
00223   ros::AdvertiseServiceOptions spawn_gazebo_model_aso =
00224     ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
00225                                                                   spawn_gazebo_model_service_name,
00226                                                                   boost::bind(&GazeboRosApiPlugin::spawnGazeboModel,this,_1,_2),
00227                                                                   ros::VoidPtr(), &gazebo_queue_);
00228   spawn_gazebo_model_service_ = nh_->advertiseService(spawn_gazebo_model_aso);
00229 
00230   // Advertise spawn services on the custom queue
00231   std::string spawn_sdf_model_service_name("spawn_sdf_model");
00232   ros::AdvertiseServiceOptions spawn_sdf_model_aso =
00233     ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
00234                                                                   spawn_sdf_model_service_name,
00235                                                                   boost::bind(&GazeboRosApiPlugin::spawnSDFModel,this,_1,_2),
00236                                                                   ros::VoidPtr(), &gazebo_queue_);
00237   spawn_sdf_model_service_ = nh_->advertiseService(spawn_sdf_model_aso);
00238 
00239   // Advertise spawn services on the custom queue
00240   std::string spawn_urdf_model_service_name("spawn_urdf_model");
00241   ros::AdvertiseServiceOptions spawn_urdf_model_aso =
00242     ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
00243                                                                   spawn_urdf_model_service_name,
00244                                                                   boost::bind(&GazeboRosApiPlugin::spawnURDFModel,this,_1,_2),
00245                                                                   ros::VoidPtr(), &gazebo_queue_);
00246   spawn_urdf_model_service_ = nh_->advertiseService(spawn_urdf_model_aso);
00247 
00248   // Advertise delete services on the custom queue
00249   std::string delete_model_service_name("delete_model");
00250   ros::AdvertiseServiceOptions delete_aso =
00251     ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
00252                                                                    delete_model_service_name,
00253                                                                    boost::bind(&GazeboRosApiPlugin::deleteModel,this,_1,_2),
00254                                                                    ros::VoidPtr(), &gazebo_queue_);
00255   delete_model_service_ = nh_->advertiseService(delete_aso);
00256 
00257   // Advertise more services on the custom queue
00258   std::string get_model_properties_service_name("get_model_properties");
00259   ros::AdvertiseServiceOptions get_model_properties_aso =
00260     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
00261                                                                           get_model_properties_service_name,
00262                                                                           boost::bind(&GazeboRosApiPlugin::getModelProperties,this,_1,_2),
00263                                                                           ros::VoidPtr(), &gazebo_queue_);
00264   get_model_properties_service_ = nh_->advertiseService(get_model_properties_aso);
00265 
00266   // Advertise more services on the custom queue
00267   std::string get_model_state_service_name("get_model_state");
00268   ros::AdvertiseServiceOptions get_model_state_aso =
00269     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
00270                                                                      get_model_state_service_name,
00271                                                                      boost::bind(&GazeboRosApiPlugin::getModelState,this,_1,_2),
00272                                                                      ros::VoidPtr(), &gazebo_queue_);
00273   get_model_state_service_ = nh_->advertiseService(get_model_state_aso);
00274 
00275   // Advertise more services on the custom queue
00276   std::string get_world_properties_service_name("get_world_properties");
00277   ros::AdvertiseServiceOptions get_world_properties_aso =
00278     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
00279                                                                           get_world_properties_service_name,
00280                                                                           boost::bind(&GazeboRosApiPlugin::getWorldProperties,this,_1,_2),
00281                                                                           ros::VoidPtr(), &gazebo_queue_);
00282   get_world_properties_service_ = nh_->advertiseService(get_world_properties_aso);
00283 
00284   // Advertise more services on the custom queue
00285   std::string get_joint_properties_service_name("get_joint_properties");
00286   ros::AdvertiseServiceOptions get_joint_properties_aso =
00287     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
00288                                                                           get_joint_properties_service_name,
00289                                                                           boost::bind(&GazeboRosApiPlugin::getJointProperties,this,_1,_2),
00290                                                                           ros::VoidPtr(), &gazebo_queue_);
00291   get_joint_properties_service_ = nh_->advertiseService(get_joint_properties_aso);
00292 
00293   // Advertise more services on the custom queue
00294   std::string get_link_properties_service_name("get_link_properties");
00295   ros::AdvertiseServiceOptions get_link_properties_aso =
00296     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
00297                                                                          get_link_properties_service_name,
00298                                                                          boost::bind(&GazeboRosApiPlugin::getLinkProperties,this,_1,_2),
00299                                                                          ros::VoidPtr(), &gazebo_queue_);
00300   get_link_properties_service_ = nh_->advertiseService(get_link_properties_aso);
00301 
00302   // Advertise more services on the custom queue
00303   std::string get_link_state_service_name("get_link_state");
00304   ros::AdvertiseServiceOptions get_link_state_aso =
00305     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
00306                                                                     get_link_state_service_name,
00307                                                                     boost::bind(&GazeboRosApiPlugin::getLinkState,this,_1,_2),
00308                                                                     ros::VoidPtr(), &gazebo_queue_);
00309   get_link_state_service_ = nh_->advertiseService(get_link_state_aso);
00310 
00311   // Advertise more services on the custom queue
00312   std::string get_physics_properties_service_name("get_physics_properties");
00313   ros::AdvertiseServiceOptions get_physics_properties_aso =
00314     ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
00315                                                                             get_physics_properties_service_name,
00316                                                                             boost::bind(&GazeboRosApiPlugin::getPhysicsProperties,this,_1,_2),
00317                                                                             ros::VoidPtr(), &gazebo_queue_);
00318   get_physics_properties_service_ = nh_->advertiseService(get_physics_properties_aso);
00319 
00320   // publish complete link states in world frame
00321   ros::AdvertiseOptions pub_link_states_ao =
00322     ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
00323                                                            "link_states",10,
00324                                                            boost::bind(&GazeboRosApiPlugin::onLinkStatesConnect,this),
00325                                                            boost::bind(&GazeboRosApiPlugin::onLinkStatesDisconnect,this),
00326                                                            ros::VoidPtr(), &gazebo_queue_);
00327   pub_link_states_ = nh_->advertise(pub_link_states_ao);
00328 
00329   // publish complete model states in world frame
00330   ros::AdvertiseOptions pub_model_states_ao =
00331     ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
00332                                                             "model_states",10,
00333                                                             boost::bind(&GazeboRosApiPlugin::onModelStatesConnect,this),
00334                                                             boost::bind(&GazeboRosApiPlugin::onModelStatesDisconnect,this),
00335                                                             ros::VoidPtr(), &gazebo_queue_);
00336   pub_model_states_ = nh_->advertise(pub_model_states_ao);
00337 
00338   // Advertise more services on the custom queue
00339   std::string set_link_properties_service_name("set_link_properties");
00340   ros::AdvertiseServiceOptions set_link_properties_aso =
00341     ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
00342                                                                          set_link_properties_service_name,
00343                                                                          boost::bind(&GazeboRosApiPlugin::setLinkProperties,this,_1,_2),
00344                                                                          ros::VoidPtr(), &gazebo_queue_);
00345   set_link_properties_service_ = nh_->advertiseService(set_link_properties_aso);
00346 
00347   // Advertise more services on the custom queue
00348   std::string set_physics_properties_service_name("set_physics_properties");
00349   ros::AdvertiseServiceOptions set_physics_properties_aso =
00350     ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
00351                                                                             set_physics_properties_service_name,
00352                                                                             boost::bind(&GazeboRosApiPlugin::setPhysicsProperties,this,_1,_2),
00353                                                                             ros::VoidPtr(), &gazebo_queue_);
00354   set_physics_properties_service_ = nh_->advertiseService(set_physics_properties_aso);
00355 
00356   // Advertise more services on the custom queue
00357   std::string set_model_state_service_name("set_model_state");
00358   ros::AdvertiseServiceOptions set_model_state_aso =
00359     ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
00360                                                                      set_model_state_service_name,
00361                                                                      boost::bind(&GazeboRosApiPlugin::setModelState,this,_1,_2),
00362                                                                      ros::VoidPtr(), &gazebo_queue_);
00363   set_model_state_service_ = nh_->advertiseService(set_model_state_aso);
00364 
00365   // Advertise more services on the custom queue
00366   std::string set_model_configuration_service_name("set_model_configuration");
00367   ros::AdvertiseServiceOptions set_model_configuration_aso =
00368     ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
00369                                                                              set_model_configuration_service_name,
00370                                                                              boost::bind(&GazeboRosApiPlugin::setModelConfiguration,this,_1,_2),
00371                                                                              ros::VoidPtr(), &gazebo_queue_);
00372   set_model_configuration_service_ = nh_->advertiseService(set_model_configuration_aso);
00373 
00374   // Advertise more services on the custom queue
00375   std::string set_joint_properties_service_name("set_joint_properties");
00376   ros::AdvertiseServiceOptions set_joint_properties_aso =
00377     ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
00378                                                                           set_joint_properties_service_name,
00379                                                                           boost::bind(&GazeboRosApiPlugin::setJointProperties,this,_1,_2),
00380                                                                           ros::VoidPtr(), &gazebo_queue_);
00381   set_joint_properties_service_ = nh_->advertiseService(set_joint_properties_aso);
00382 
00383   // Advertise more services on the custom queue
00384   std::string set_link_state_service_name("set_link_state");
00385   ros::AdvertiseServiceOptions set_link_state_aso =
00386     ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
00387                                                                     set_link_state_service_name,
00388                                                                     boost::bind(&GazeboRosApiPlugin::setLinkState,this,_1,_2),
00389                                                                     ros::VoidPtr(), &gazebo_queue_);
00390   set_link_state_service_ = nh_->advertiseService(set_link_state_aso);
00391 
00392   // Advertise topic on custom queue
00393   // topic callback version for set_link_state
00394   ros::SubscribeOptions link_state_so =
00395     ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
00396                                                           "set_link_state",10,
00397                                                           boost::bind( &GazeboRosApiPlugin::updateLinkState,this,_1),
00398                                                           ros::VoidPtr(), &gazebo_queue_);
00399   set_link_state_topic_ = nh_->subscribe(link_state_so);
00400 
00401   // topic callback version for set_model_state
00402   ros::SubscribeOptions model_state_so =
00403     ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
00404                                                            "set_model_state",10,
00405                                                            boost::bind( &GazeboRosApiPlugin::updateModelState,this,_1),
00406                                                            ros::VoidPtr(), &gazebo_queue_);
00407   set_model_state_topic_ = nh_->subscribe(model_state_so);
00408 
00409   // Advertise more services on the custom queue
00410   std::string pause_physics_service_name("pause_physics");
00411   ros::AdvertiseServiceOptions pause_physics_aso =
00412     ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00413                                                           pause_physics_service_name,
00414                                                           boost::bind(&GazeboRosApiPlugin::pausePhysics,this,_1,_2),
00415                                                           ros::VoidPtr(), &gazebo_queue_);
00416   pause_physics_service_ = nh_->advertiseService(pause_physics_aso);
00417 
00418   // Advertise more services on the custom queue
00419   std::string unpause_physics_service_name("unpause_physics");
00420   ros::AdvertiseServiceOptions unpause_physics_aso =
00421     ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00422                                                           unpause_physics_service_name,
00423                                                           boost::bind(&GazeboRosApiPlugin::unpausePhysics,this,_1,_2),
00424                                                           ros::VoidPtr(), &gazebo_queue_);
00425   unpause_physics_service_ = nh_->advertiseService(unpause_physics_aso);
00426 
00427   // Advertise more services on the custom queue
00428   std::string apply_body_wrench_service_name("apply_body_wrench");
00429   ros::AdvertiseServiceOptions apply_body_wrench_aso =
00430     ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
00431                                                                        apply_body_wrench_service_name,
00432                                                                        boost::bind(&GazeboRosApiPlugin::applyBodyWrench,this,_1,_2),
00433                                                                        ros::VoidPtr(), &gazebo_queue_);
00434   apply_body_wrench_service_ = nh_->advertiseService(apply_body_wrench_aso);
00435 
00436   // Advertise more services on the custom queue
00437   std::string apply_joint_effort_service_name("apply_joint_effort");
00438   ros::AdvertiseServiceOptions apply_joint_effort_aso =
00439     ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
00440                                                                         apply_joint_effort_service_name,
00441                                                                         boost::bind(&GazeboRosApiPlugin::applyJointEffort,this,_1,_2),
00442                                                                         ros::VoidPtr(), &gazebo_queue_);
00443   apply_joint_effort_service_ = nh_->advertiseService(apply_joint_effort_aso);
00444 
00445   // Advertise more services on the custom queue
00446   std::string clear_joint_forces_service_name("clear_joint_forces");
00447   ros::AdvertiseServiceOptions clear_joint_forces_aso =
00448     ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
00449                                                                     clear_joint_forces_service_name,
00450                                                                     boost::bind(&GazeboRosApiPlugin::clearJointForces,this,_1,_2),
00451                                                                     ros::VoidPtr(), &gazebo_queue_);
00452   clear_joint_forces_service_ = nh_->advertiseService(clear_joint_forces_aso);
00453 
00454   // Advertise more services on the custom queue
00455   std::string clear_body_wrenches_service_name("clear_body_wrenches");
00456   ros::AdvertiseServiceOptions clear_body_wrenches_aso =
00457     ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
00458                                                                    clear_body_wrenches_service_name,
00459                                                                    boost::bind(&GazeboRosApiPlugin::clearBodyWrenches,this,_1,_2),
00460                                                                    ros::VoidPtr(), &gazebo_queue_);
00461   clear_body_wrenches_service_ = nh_->advertiseService(clear_body_wrenches_aso);
00462 
00463   // Advertise more services on the custom queue
00464   std::string reset_simulation_service_name("reset_simulation");
00465   ros::AdvertiseServiceOptions reset_simulation_aso =
00466     ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00467                                                           reset_simulation_service_name,
00468                                                           boost::bind(&GazeboRosApiPlugin::resetSimulation,this,_1,_2),
00469                                                           ros::VoidPtr(), &gazebo_queue_);
00470   reset_simulation_service_ = nh_->advertiseService(reset_simulation_aso);
00471 
00472   // Advertise more services on the custom queue
00473   std::string reset_world_service_name("reset_world");
00474   ros::AdvertiseServiceOptions reset_world_aso =
00475     ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00476                                                           reset_world_service_name,
00477                                                           boost::bind(&GazeboRosApiPlugin::resetWorld,this,_1,_2),
00478                                                           ros::VoidPtr(), &gazebo_queue_);
00479   reset_world_service_ = nh_->advertiseService(reset_world_aso);
00480 
00481 
00482   // set param for use_sim_time if not set by user already
00483   nh_->setParam("/use_sim_time", true);
00484 
00485   // todo: contemplate setting environment variable ROBOT=sim here???
00486   nh_->getParam("pub_clock_frequency", pub_clock_frequency_);
00487   last_pub_clock_time_ = world_->GetSimTime();
00488 }
00489 
00490 void GazeboRosApiPlugin::onLinkStatesConnect()
00491 {
00492   pub_link_states_connection_count_++;
00493   if (pub_link_states_connection_count_ == 1) // connect on first subscriber
00494     pub_link_states_event_   = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishLinkStates,this));
00495 }
00496 
00497 void GazeboRosApiPlugin::onModelStatesConnect()
00498 {
00499   pub_model_states_connection_count_++;
00500   if (pub_model_states_connection_count_ == 1) // connect on first subscriber
00501     pub_model_states_event_   = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishModelStates,this));
00502 }
00503 
00504 void GazeboRosApiPlugin::onLinkStatesDisconnect()
00505 {
00506   pub_link_states_connection_count_--;
00507   if (pub_link_states_connection_count_ <= 0) // disconnect with no subscribers
00508   {
00509     gazebo::event::Events::DisconnectWorldUpdateBegin(pub_link_states_event_);
00510     if (pub_link_states_connection_count_ < 0) // should not be possible
00511       ROS_ERROR("one too mandy disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
00512   }
00513 }
00514 
00515 void GazeboRosApiPlugin::onModelStatesDisconnect()
00516 {
00517   pub_model_states_connection_count_--;
00518   if (pub_model_states_connection_count_ <= 0) // disconnect with no subscribers
00519   {
00520     gazebo::event::Events::DisconnectWorldUpdateBegin(pub_model_states_event_);
00521     if (pub_model_states_connection_count_ < 0) // should not be possible
00522       ROS_ERROR("one too mandy disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
00523   }
00524 }
00525 
00526 bool GazeboRosApiPlugin::spawnURDFModel(gazebo_msgs::SpawnModel::Request &req,
00527                                         gazebo_msgs::SpawnModel::Response &res)
00528 {
00529   // get name space for the corresponding model plugins
00530   robot_namespace_ = req.robot_namespace;
00531 
00532   // incoming robot model string
00533   std::string model_xml = req.model_xml;
00534 
00535   if (!isURDF(model_xml))
00536   {
00537     ROS_ERROR("SpawnModel: Failure - model format is not URDF.");
00538     res.success = false;
00539     res.status_message = "SpawnModel: Failure - model format is not URDF.";
00540     return false;
00541   }
00542 
00546   {
00547     std::string open_bracket("<?");
00548     std::string close_bracket("?>");
00549     size_t pos1 = model_xml.find(open_bracket,0);
00550     size_t pos2 = model_xml.find(close_bracket,0);
00551     if (pos1 != std::string::npos && pos2 != std::string::npos)
00552       model_xml.replace(pos1,pos2-pos1+2,std::string(""));
00553   }
00554 
00555   // Now, replace package://xxx with the full path to the package
00556   {
00557     std::string package_prefix("package://");
00558     size_t pos1 = model_xml.find(package_prefix,0);
00559     while (pos1 != std::string::npos)
00560     {
00561       size_t pos2 = model_xml.find("/", pos1+10);
00562       //ROS_DEBUG(" pos %d %d",(int)pos1, (int)pos2);
00563       if (pos2 == std::string::npos || pos1 >= pos2)
00564       {
00565         ROS_ERROR("malformed package name?");
00566         break;
00567       }
00568 
00569       std::string package_name = model_xml.substr(pos1+10,pos2-pos1-10);
00570       //ROS_DEBUG("package name [%s]", package_name.c_str());
00571       std::string package_path = ros::package::getPath(package_name);
00572       if (package_path.empty())
00573       {
00574         ROS_FATAL("Package[%s] does not have a path",package_name.c_str());
00575         res.success = false;
00576         res.status_message = std::string("urdf reference package name does not exist: ")+package_name;
00577         return false;
00578       }
00579       ROS_DEBUG_ONCE("Package name [%s] has path [%s]", package_name.c_str(), package_path.c_str());
00580 
00581       model_xml.replace(pos1,(pos2-pos1),package_path);
00582       pos1 = model_xml.find(package_prefix, pos1);
00583     }
00584   }
00585   // ROS_DEBUG("Model XML\n\n%s\n\n ",model_xml.c_str());
00586 
00587   req.model_xml = model_xml;
00588 
00589   // Model is now considered convert to SDF
00590   return spawnSDFModel(req,res);
00591 }
00592 
00593 // DEPRECATED IN HYDRO
00594 bool GazeboRosApiPlugin::spawnGazeboModel(gazebo_msgs::SpawnModel::Request &req,
00595                                           gazebo_msgs::SpawnModel::Response &res)
00596 {
00597   ROS_WARN_STREAM_NAMED("api_plugin","/gazebo/spawn_gazebo_model is deprecated, use /gazebo/spawn_sdf_model instead");
00598   spawnSDFModel(req, res);
00599 }
00600 
00601 bool GazeboRosApiPlugin::spawnSDFModel(gazebo_msgs::SpawnModel::Request &req,
00602                                        gazebo_msgs::SpawnModel::Response &res)
00603 {
00604   // incoming robot name
00605   std::string model_name = req.model_name;
00606 
00607   // get name space for the corresponding model plugins
00608   robot_namespace_ = req.robot_namespace;
00609 
00610   // get initial pose of model
00611   gazebo::math::Vector3 initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
00612   // get initial roll pitch yaw (fixed frame transform)
00613   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);
00614 
00615   // refernce frame for initial pose definition, modify initial pose if defined
00616   gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.reference_frame));
00617   if (frame)
00618   {
00619     // convert to relative pose
00620     gazebo::math::Pose frame_pose = frame->GetWorldPose();
00621     initial_xyz = frame_pose.rot.RotateVector(initial_xyz);
00622     initial_xyz += frame_pose.pos;
00623     initial_q *= frame_pose.rot;
00624   }
00625 
00627   else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
00628   {
00629     ROS_DEBUG("SpawnModel: reference_frame is empty/world/map, using inertial frame");
00630   }
00631   else
00632   {
00633     res.success = false;
00634     res.status_message = "SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
00635     return true;
00636   }
00637 
00638   // incoming robot model string
00639   std::string model_xml = req.model_xml;
00640 
00641   // store resulting Gazebo Model XML to be sent to spawn queue
00642   // get incoming string containg either an URDF or a Gazebo Model XML
00643   // grab from parameter server if necessary convert to SDF if necessary
00644   stripXmlDeclaration(model_xml);
00645 
00646   // put string in TiXmlDocument for manipulation
00647   TiXmlDocument gazebo_model_xml;
00648   gazebo_model_xml.Parse(model_xml.c_str());
00649 
00650   // optional model manipulations: update initial pose && replace model name
00651   if (isSDF(model_xml))
00652   {
00653     updateSDFAttributes(gazebo_model_xml, model_name, initial_xyz, initial_q);
00654 
00655     // Walk recursively through the entire SDF, locate plugin tags and
00656     // add robotNamespace as a child with the correct namespace
00657     if (!this->robot_namespace_.empty())
00658     {
00659       // Get root element for SDF
00660       TiXmlNode* model_tixml = gazebo_model_xml.FirstChild("sdf");
00661       model_tixml = (!model_tixml) ?
00662           gazebo_model_xml.FirstChild("gazebo") : model_tixml;
00663       if (model_tixml)
00664       {
00665         walkChildAddRobotNamespace(model_tixml);
00666       }
00667       else
00668       {
00669         ROS_WARN("Unable to add robot namespace to xml");
00670       }
00671     }
00672   }
00673   else if (isURDF(model_xml))
00674   {
00675     updateURDFModelPose(gazebo_model_xml, initial_xyz, initial_q);
00676     updateURDFName(gazebo_model_xml, model_name);
00677 
00678     // Walk recursively through the entire URDF, locate plugin tags and
00679     // add robotNamespace as a child with the correct namespace
00680     if (!this->robot_namespace_.empty())
00681     {
00682       // Get root element for URDF
00683       TiXmlNode* model_tixml = gazebo_model_xml.FirstChild("robot");
00684       if (model_tixml)
00685       {
00686         walkChildAddRobotNamespace(model_tixml);
00687       }
00688       else
00689       {
00690         ROS_WARN("Unable to add robot namespace to xml");
00691       }
00692     }
00693   }
00694   else
00695   {
00696     ROS_ERROR("GazeboRosApiPlugin SpawnModel Failure: input xml format not recognized");
00697     res.success = false;
00698     res.status_message = std::string("GazeboRosApiPlugin SpawnModel Failure: input model_xml not SDF or URDF, or cannot be converted to Gazebo compatible format.");
00699     return true;
00700   }
00701 
00702   // do spawning check if spawn worked, return response
00703   return spawnAndConform(gazebo_model_xml, model_name, res);
00704 }
00705 
00706 bool GazeboRosApiPlugin::deleteModel(gazebo_msgs::DeleteModel::Request &req,
00707                                      gazebo_msgs::DeleteModel::Response &res)
00708 {
00709   // clear forces, etc for the body in question
00710   gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
00711   if (!model)
00712   {
00713     ROS_ERROR("DeleteModel: model [%s] does not exist",req.model_name.c_str());
00714     res.success = false;
00715     res.status_message = "DeleteModel: model does not exist";
00716     return true;
00717   }
00718 
00719   // delete wrench jobs on bodies
00720   for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
00721   {
00722     gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
00723     if (body)
00724     {
00725       // look for it in jobs, delete body wrench jobs
00726       clearBodyWrenches(body->GetScopedName());
00727     }
00728   }
00729 
00730   // delete force jobs on joints
00731   gazebo::physics::Joint_V joints = model->GetJoints();
00732   for (unsigned int i=0;i< joints.size(); i++)
00733   {
00734     // look for it in jobs, delete joint force jobs
00735     clearJointForces(joints[i]->GetName());
00736   }
00737 
00738   // send delete model request
00739   gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest("entity_delete",req.model_name);
00740   request_pub_->Publish(*msg,true);
00741 
00742   ros::Duration model_spawn_timeout(60.0);
00743   ros::Time timeout = ros::Time::now() + model_spawn_timeout;
00744   // wait and verify that model is deleted
00745   while (true)
00746   {
00747     if (ros::Time::now() > timeout)
00748     {
00749       res.success = false;
00750       res.status_message = std::string("DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation");
00751       return true;
00752     }
00753     {
00754       //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
00755       if (!world_->GetModel(req.model_name)) break;
00756     }
00757     ROS_DEBUG("Waiting for model deletion (%s)",req.model_name.c_str());
00758     usleep(1000);
00759   }
00760 
00761   // set result
00762   res.success = true;
00763   res.status_message = std::string("DeleteModel: successfully deleted model");
00764   return true;
00765 }
00766 
00767 bool GazeboRosApiPlugin::getModelState(gazebo_msgs::GetModelState::Request &req,
00768                                        gazebo_msgs::GetModelState::Response &res)
00769 {
00770   gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
00771   gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.relative_entity_name));
00772   if (!model)
00773   {
00774     ROS_ERROR("GetModelState: model [%s] does not exist",req.model_name.c_str());
00775     res.success = false;
00776     res.status_message = "GetModelState: model does not exist";
00777     return true;
00778   }
00779   else
00780   {
00786     {
00787       std::map<std::string, unsigned int>::iterator it = access_count_get_model_state_.find(req.model_name);
00788       if(it == access_count_get_model_state_.end()) 
00789       {
00790         access_count_get_model_state_.insert( std::pair<std::string, unsigned int>(req.model_name, 1) );
00791         res.header.seq = 1;
00792       } 
00793       else 
00794       {
00795         it->second++;
00796         res.header.seq = it->second;
00797       }
00798       res.header.stamp = ros::Time::now();
00799       res.header.frame_id = req.relative_entity_name; 
00800     }
00801     // get model pose
00802     gazebo::math::Pose       model_pose = model->GetWorldPose();
00803     gazebo::math::Vector3    model_pos = model_pose.pos;
00804     gazebo::math::Quaternion model_rot = model_pose.rot;
00805 
00806     // get model twist
00807     gazebo::math::Vector3 model_linear_vel  = model->GetWorldLinearVel();
00808     gazebo::math::Vector3 model_angular_vel = model->GetWorldAngularVel();
00809 
00810 
00811     if (frame)
00812     {
00813       // convert to relative pose
00814       gazebo::math::Pose frame_pose = frame->GetWorldPose();
00815       model_pos = model_pos - frame_pose.pos;
00816       model_pos = frame_pose.rot.RotateVectorReverse(model_pos);
00817       model_rot *= frame_pose.rot.GetInverse();
00818 
00819       // convert to relative rates
00820       gazebo::math::Vector3 frame_vpos = frame->GetWorldLinearVel(); // get velocity in gazebo frame
00821       gazebo::math::Vector3 frame_veul = frame->GetWorldAngularVel(); // get velocity in gazebo frame
00822       model_linear_vel = frame_pose.rot.RotateVector(model_linear_vel - frame_vpos);
00823       model_angular_vel = frame_pose.rot.RotateVector(model_angular_vel - frame_veul);
00824     }
00826     else if (req.relative_entity_name == "" || req.relative_entity_name == "world" || req.relative_entity_name == "map" || req.relative_entity_name == "/map")
00827     {
00828       ROS_DEBUG("GetModelState: relative_entity_name is empty/world/map, using inertial frame");
00829     }
00830     else
00831     {
00832       res.success = false;
00833       res.status_message = "GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
00834       return true;
00835     }
00836 
00837     // fill in response
00838     res.pose.position.x = model_pos.x;
00839     res.pose.position.y = model_pos.y;
00840     res.pose.position.z = model_pos.z;
00841     res.pose.orientation.w = model_rot.w;
00842     res.pose.orientation.x = model_rot.x;
00843     res.pose.orientation.y = model_rot.y;
00844     res.pose.orientation.z = model_rot.z;
00845 
00846     res.twist.linear.x = model_linear_vel.x;
00847     res.twist.linear.y = model_linear_vel.y;
00848     res.twist.linear.z = model_linear_vel.z;
00849     res.twist.angular.x = model_angular_vel.x;
00850     res.twist.angular.y = model_angular_vel.y;
00851     res.twist.angular.z = model_angular_vel.z;
00852 
00853     res.success = true;
00854     res.status_message = "GetModelState: got properties";
00855     return true;
00856   }
00857   return true;
00858 }
00859 
00860 bool GazeboRosApiPlugin::getModelProperties(gazebo_msgs::GetModelProperties::Request &req,
00861                                             gazebo_msgs::GetModelProperties::Response &res)
00862 {
00863   gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
00864   if (!model)
00865   {
00866     ROS_ERROR("GetModelProperties: model [%s] does not exist",req.model_name.c_str());
00867     res.success = false;
00868     res.status_message = "GetModelProperties: model does not exist";
00869     return true;
00870   }
00871   else
00872   {
00873     // get model parent name
00874     gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
00875     if (parent_model) res.parent_model_name = parent_model->GetName();
00876 
00877     // get list of child bodies, geoms
00878     res.body_names.clear();
00879     res.geom_names.clear();
00880     for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
00881     {
00882       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
00883       if (body)
00884       {
00885         res.body_names.push_back(body->GetName());
00886         // get list of geoms
00887         for (unsigned int j = 0; j < body->GetChildCount() ; j++)
00888         {
00889           gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
00890           if (geom)
00891             res.geom_names.push_back(geom->GetName());
00892         }
00893       }
00894     }
00895 
00896     // get list of joints
00897     res.joint_names.clear();
00898 
00899     gazebo::physics::Joint_V joints = model->GetJoints();
00900     for (unsigned int i=0;i< joints.size(); i++)
00901       res.joint_names.push_back( joints[i]->GetName() );
00902 
00903     // get children model names
00904     res.child_model_names.clear();
00905     for (unsigned int j = 0; j < model->GetChildCount(); j++)
00906     {
00907       gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
00908       if (child_model)
00909         res.child_model_names.push_back(child_model->GetName() );
00910     }
00911 
00912     // is model static
00913     res.is_static = model->IsStatic();
00914 
00915     res.success = true;
00916     res.status_message = "GetModelProperties: got properties";
00917     return true;
00918   }
00919   return true;
00920 }
00921 
00922 bool GazeboRosApiPlugin::getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,
00923                                             gazebo_msgs::GetWorldProperties::Response &res)
00924 {
00925   res.sim_time = world_->GetSimTime().Double();
00926   res.model_names.clear();
00927   for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
00928     res.model_names.push_back(world_->GetModel(i)->GetName());
00929   gzerr << "disablign rendering has not been implemented, rendering is always enabled\n";
00930   res.rendering_enabled = true; //world->GetRenderEngineEnabled();
00931   res.success = true;
00932   res.status_message = "GetWorldProperties: got properties";
00933   return true;
00934 }
00935 
00936 bool GazeboRosApiPlugin::getJointProperties(gazebo_msgs::GetJointProperties::Request &req,
00937                                             gazebo_msgs::GetJointProperties::Response &res)
00938 {
00939   gazebo::physics::JointPtr joint;
00940   for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
00941   {
00942     joint = world_->GetModel(i)->GetJoint(req.joint_name);
00943     if (joint) break;
00944   }
00945 
00946   if (!joint)
00947   {
00948     res.success = false;
00949     res.status_message = "GetJointProperties: joint not found";
00950     return true;
00951   }
00952   else
00953   {
00955     res.type = res.REVOLUTE;
00956 
00957     res.damping.clear(); // to be added to gazebo
00958     //res.damping.push_back(joint->GetDamping(0));
00959 
00960     res.position.clear(); // use GetAngle(i)
00961     res.position.push_back(joint->GetAngle(0).Radian());
00962 
00963     res.rate.clear(); // use GetVelocity(i)
00964     res.rate.push_back(joint->GetVelocity(0));
00965 
00966     res.success = true;
00967     res.status_message = "GetJointProperties: got properties";
00968     return true;
00969   }
00970 }
00971 
00972 bool GazeboRosApiPlugin::getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,
00973                                            gazebo_msgs::GetLinkProperties::Response &res)
00974 {
00975   gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
00976   if (!body)
00977   {
00978     res.success = false;
00979     res.status_message = "GetLinkProperties: link not found, did you forget to scope the link by model name?";
00980     return true;
00981   }
00982   else
00983   {
00985     res.gravity_mode = body->GetGravityMode();
00986 
00987     res.mass = body->GetInertial()->GetMass();
00988 
00989     gazebo::physics::InertialPtr inertia = body->GetInertial();
00990     res.ixx = inertia->GetIXX();
00991     res.iyy = inertia->GetIYY();
00992     res.izz = inertia->GetIZZ();
00993     res.ixy = inertia->GetIXY();
00994     res.ixz = inertia->GetIXZ();
00995     res.iyz = inertia->GetIYZ();
00996 
00997     gazebo::math::Vector3 com = body->GetInertial()->GetCoG();
00998     res.com.position.x = com.x;
00999     res.com.position.y = com.y;
01000     res.com.position.z = com.z;
01001     res.com.orientation.x = 0; // @todo: gazebo do not support rotated inertia yet
01002     res.com.orientation.y = 0;
01003     res.com.orientation.z = 0;
01004     res.com.orientation.w = 1;
01005 
01006     res.success = true;
01007     res.status_message = "GetLinkProperties: got properties";
01008     return true;
01009   }
01010 }
01011 
01012 bool GazeboRosApiPlugin::getLinkState(gazebo_msgs::GetLinkState::Request &req,
01013                                       gazebo_msgs::GetLinkState::Response &res)
01014 {
01015   gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
01016   gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.reference_frame));
01017 
01018   if (!body)
01019   {
01020     res.success = false;
01021     res.status_message = "GetLinkState: link not found, did you forget to scope the link by model name?";
01022     return true;
01023   }
01024 
01025   // get body pose
01026   gazebo::math::Pose body_pose = body->GetWorldPose();
01027   // Get inertial rates
01028   gazebo::math::Vector3 body_vpos = body->GetWorldLinearVel(); // get velocity in gazebo frame
01029   gazebo::math::Vector3 body_veul = body->GetWorldAngularVel(); // get velocity in gazebo frame
01030 
01031   if (frame)
01032   {
01033     // convert to relative pose
01034     gazebo::math::Pose frame_pose = frame->GetWorldPose();
01035     body_pose.pos = body_pose.pos - frame_pose.pos;
01036     body_pose.pos = frame_pose.rot.RotateVectorReverse(body_pose.pos);
01037     body_pose.rot *= frame_pose.rot.GetInverse();
01038 
01039     // convert to relative rates
01040     gazebo::math::Vector3 frame_vpos = frame->GetWorldLinearVel(); // get velocity in gazebo frame
01041     gazebo::math::Vector3 frame_veul = frame->GetWorldAngularVel(); // get velocity in gazebo frame
01042     body_vpos = frame_pose.rot.RotateVector(body_vpos - frame_vpos);
01043     body_veul = frame_pose.rot.RotateVector(body_veul - frame_veul);
01044   }
01046   else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
01047   {
01048     ROS_DEBUG("GetLinkState: reference_frame is empty/world/map, using inertial frame");
01049   }
01050   else
01051   {
01052     res.success = false;
01053     res.status_message = "GetLinkState: reference reference_frame not found, did you forget to scope the link by model name?";
01054     return true;
01055   }
01056 
01057   res.link_state.link_name = req.link_name;
01058   res.link_state.pose.position.x = body_pose.pos.x;
01059   res.link_state.pose.position.y = body_pose.pos.y;
01060   res.link_state.pose.position.z = body_pose.pos.z;
01061   res.link_state.pose.orientation.x = body_pose.rot.x;
01062   res.link_state.pose.orientation.y = body_pose.rot.y;
01063   res.link_state.pose.orientation.z = body_pose.rot.z;
01064   res.link_state.pose.orientation.w = body_pose.rot.w;
01065   res.link_state.twist.linear.x = body_vpos.x;
01066   res.link_state.twist.linear.y = body_vpos.y;
01067   res.link_state.twist.linear.z = body_vpos.z;
01068   res.link_state.twist.angular.x = body_veul.x;
01069   res.link_state.twist.angular.y = body_veul.y;
01070   res.link_state.twist.angular.z = body_veul.z;
01071   res.link_state.reference_frame = req.reference_frame;
01072 
01073   res.success = true;
01074   res.status_message = "GetLinkState: got state";
01075   return true;
01076 }
01077 
01078 bool GazeboRosApiPlugin::setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req,
01079                                            gazebo_msgs::SetLinkProperties::Response &res)
01080 {
01081   gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
01082   if (!body)
01083   {
01084     res.success = false;
01085     res.status_message = "SetLinkProperties: link not found, did you forget to scope the link by model name?";
01086     return true;
01087   }
01088   else
01089   {
01090     gazebo::physics::InertialPtr mass = body->GetInertial();
01091     // @todo: FIXME: add inertia matrix rotation to Gazebo
01092     // mass.SetInertiaRotation(gazebo::math::Quaternionion(req.com.orientation.w,res.com.orientation.x,req.com.orientation.y req.com.orientation.z));
01093     mass->SetCoG(gazebo::math::Vector3(req.com.position.x,req.com.position.y,req.com.position.z));
01094     mass->SetInertiaMatrix(req.ixx,req.iyy,req.izz,req.ixy,req.ixz,req.iyz);
01095     mass->SetMass(req.mass);
01096     body->SetGravityMode(req.gravity_mode);
01097     // @todo: mass change unverified
01098     res.success = true;
01099     res.status_message = "SetLinkProperties: properties set";
01100     return true;
01101   }
01102 }
01103 
01104 bool GazeboRosApiPlugin::setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req,
01105                                               gazebo_msgs::SetPhysicsProperties::Response &res)
01106 {
01107   // pause simulation if requested
01108   bool is_paused = world_->IsPaused();
01109   world_->SetPaused(true);
01110 
01111   // supported updates
01112   gazebo::physics::PhysicsEnginePtr pe = (world_->GetPhysicsEngine());
01113   pe->SetMaxStepSize(req.time_step);
01114   pe->SetRealTimeUpdateRate(req.max_update_rate);
01115   pe->SetGravity(gazebo::math::Vector3(req.gravity.x,req.gravity.y,req.gravity.z));
01116 
01117   if (world_->GetPhysicsEngine()->GetType() == "ode")
01118   {
01119     // stuff only works in ODE right now
01120     pe->SetAutoDisableFlag(req.ode_config.auto_disable_bodies);
01121 #if GAZEBO_MAJOR_VERSION >= 3
01122     pe->SetParam("precon_iters", req.ode_config.sor_pgs_precon_iters);
01123     pe->SetParam("iters", req.ode_config.sor_pgs_iters);
01124     pe->SetParam("sor", req.ode_config.sor_pgs_w);
01125     pe->SetParam("cfm", req.ode_config.cfm);
01126     pe->SetParam("erp", req.ode_config.erp);
01127     pe->SetParam("contact_surface_layer",
01128         req.ode_config.contact_surface_layer);
01129     pe->SetParam("contact_max_correcting_vel",
01130         req.ode_config.contact_max_correcting_vel);
01131     pe->SetParam("max_contacts", req.ode_config.max_contacts);
01132 #else
01133     pe->SetSORPGSPreconIters(req.ode_config.sor_pgs_precon_iters);
01134     pe->SetSORPGSIters(req.ode_config.sor_pgs_iters);
01135     pe->SetSORPGSW(req.ode_config.sor_pgs_w);
01136     pe->SetWorldCFM(req.ode_config.cfm);
01137     pe->SetWorldERP(req.ode_config.erp);
01138     pe->SetContactSurfaceLayer(req.ode_config.contact_surface_layer);
01139     pe->SetContactMaxCorrectingVel(req.ode_config.contact_max_correcting_vel);
01140     pe->SetMaxContacts(req.ode_config.max_contacts);
01141 #endif
01142 
01143     world_->SetPaused(is_paused);
01144 
01145     res.success = true;
01146     res.status_message = "physics engine updated";
01147   }
01148   else
01149   {
01151     ROS_ERROR("ROS set_physics_properties service call does not yet support physics engine [%s].", world_->GetPhysicsEngine()->GetType().c_str());
01152     res.success = false;
01153     res.status_message = "Physics engine [" + world_->GetPhysicsEngine()->GetType() + "]: set_physics_properties not supported.";
01154   }
01155   return res.success;
01156 }
01157 
01158 bool GazeboRosApiPlugin::getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req,
01159                                               gazebo_msgs::GetPhysicsProperties::Response &res)
01160 {
01161   // supported updates
01162   res.time_step = world_->GetPhysicsEngine()->GetMaxStepSize();
01163   res.pause = world_->IsPaused();
01164   res.max_update_rate = world_->GetPhysicsEngine()->GetRealTimeUpdateRate();
01165   gazebo::math::Vector3 gravity = world_->GetPhysicsEngine()->GetGravity();
01166   res.gravity.x = gravity.x;
01167   res.gravity.y = gravity.y;
01168   res.gravity.z = gravity.z;
01169 
01170   // stuff only works in ODE right now
01171   if (world_->GetPhysicsEngine()->GetType() == "ode")
01172   {
01173     res.ode_config.auto_disable_bodies =
01174       world_->GetPhysicsEngine()->GetAutoDisableFlag();
01175 #if GAZEBO_MAJOR_VERSION >= 3
01176     res.ode_config.sor_pgs_precon_iters = boost::any_cast<int>(
01177       world_->GetPhysicsEngine()->GetParam("precon_iters"));
01178     res.ode_config.sor_pgs_iters = boost::any_cast<int>(
01179         world_->GetPhysicsEngine()->GetParam("iters"));
01180     res.ode_config.sor_pgs_w = boost::any_cast<double>(
01181         world_->GetPhysicsEngine()->GetParam("sor"));
01182     res.ode_config.contact_surface_layer = boost::any_cast<double>(
01183       world_->GetPhysicsEngine()->GetParam("contact_surface_layer"));
01184     res.ode_config.contact_max_correcting_vel = boost::any_cast<double>(
01185       world_->GetPhysicsEngine()->GetParam("contact_max_correcting_vel"));
01186     res.ode_config.cfm = boost::any_cast<double>(
01187         world_->GetPhysicsEngine()->GetParam("cfm"));
01188     res.ode_config.erp = boost::any_cast<double>(
01189         world_->GetPhysicsEngine()->GetParam("erp"));
01190     res.ode_config.max_contacts = boost::any_cast<int>(
01191       world_->GetPhysicsEngine()->GetParam("max_contacts"));
01192 #else
01193     res.ode_config.sor_pgs_precon_iters = world_->GetPhysicsEngine()->GetSORPGSPreconIters();
01194     res.ode_config.sor_pgs_iters = world_->GetPhysicsEngine()->GetSORPGSIters();
01195     res.ode_config.sor_pgs_w = world_->GetPhysicsEngine()->GetSORPGSW();
01196     res.ode_config.contact_surface_layer = world_->GetPhysicsEngine()->GetContactSurfaceLayer();
01197     res.ode_config.contact_max_correcting_vel = world_->GetPhysicsEngine()->GetContactMaxCorrectingVel();
01198     res.ode_config.cfm = world_->GetPhysicsEngine()->GetWorldCFM();
01199     res.ode_config.erp = world_->GetPhysicsEngine()->GetWorldERP();
01200     res.ode_config.max_contacts = world_->GetPhysicsEngine()->GetMaxContacts();
01201 #endif
01202 
01203     res.success = true;
01204     res.status_message = "GetPhysicsProperties: got properties";
01205   }
01206   else
01207   {
01209     ROS_ERROR("ROS get_physics_properties service call does not yet support physics engine [%s].", world_->GetPhysicsEngine()->GetType().c_str());
01210     res.success = false;
01211     res.status_message = "Physics engine [" + world_->GetPhysicsEngine()->GetType() + "]: get_physics_properties not supported.";
01212   }
01213   return res.success;
01214 }
01215 
01216 bool GazeboRosApiPlugin::setJointProperties(gazebo_msgs::SetJointProperties::Request &req,
01217                                             gazebo_msgs::SetJointProperties::Response &res)
01218 {
01220   gazebo::physics::JointPtr joint;
01221   for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
01222   {
01223     joint = world_->GetModel(i)->GetJoint(req.joint_name);
01224     if (joint) break;
01225   }
01226 
01227   if (!joint)
01228   {
01229     res.success = false;
01230     res.status_message = "SetJointProperties: joint not found";
01231     return true;
01232   }
01233   else
01234   {
01235     for(unsigned int i=0;i< req.ode_joint_config.damping.size();i++)
01236       joint->SetDamping(i,req.ode_joint_config.damping[i]);
01237 #if GAZEBO_MAJOR_VERSION >= 4
01238     for(unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
01239       joint->SetParam("hi_stop",i,req.ode_joint_config.hiStop[i]);
01240     for(unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
01241       joint->SetParam("lo_stop",i,req.ode_joint_config.loStop[i]);
01242     for(unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
01243       joint->SetParam("erp",i,req.ode_joint_config.erp[i]);
01244     for(unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
01245       joint->SetParam("cfm",i,req.ode_joint_config.cfm[i]);
01246     for(unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
01247       joint->SetParam("stop_erp",i,req.ode_joint_config.stop_erp[i]);
01248     for(unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
01249       joint->SetParam("stop_cfm",i,req.ode_joint_config.stop_cfm[i]);
01250     for(unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
01251       joint->SetParam("fudge_factor",i,req.ode_joint_config.fudge_factor[i]);
01252     for(unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
01253       joint->SetParam("fmax",i,req.ode_joint_config.fmax[i]);
01254     for(unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
01255       joint->SetParam("vel",i,req.ode_joint_config.vel[i]);
01256 #else
01257     for(unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
01258       joint->SetAttribute("hi_stop",i,req.ode_joint_config.hiStop[i]);
01259     for(unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
01260       joint->SetAttribute("lo_stop",i,req.ode_joint_config.loStop[i]);
01261     for(unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
01262       joint->SetAttribute("erp",i,req.ode_joint_config.erp[i]);
01263     for(unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
01264       joint->SetAttribute("cfm",i,req.ode_joint_config.cfm[i]);
01265     for(unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
01266       joint->SetAttribute("stop_erp",i,req.ode_joint_config.stop_erp[i]);
01267     for(unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
01268       joint->SetAttribute("stop_cfm",i,req.ode_joint_config.stop_cfm[i]);
01269     for(unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
01270       joint->SetAttribute("fudge_factor",i,req.ode_joint_config.fudge_factor[i]);
01271     for(unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
01272       joint->SetAttribute("fmax",i,req.ode_joint_config.fmax[i]);
01273     for(unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
01274       joint->SetAttribute("vel",i,req.ode_joint_config.vel[i]);
01275 #endif
01276 
01277     res.success = true;
01278     res.status_message = "SetJointProperties: properties set";
01279     return true;
01280   }
01281 }
01282 
01283 bool GazeboRosApiPlugin::setModelState(gazebo_msgs::SetModelState::Request &req,
01284                                        gazebo_msgs::SetModelState::Response &res)
01285 {
01286   gazebo::math::Vector3 target_pos(req.model_state.pose.position.x,req.model_state.pose.position.y,req.model_state.pose.position.z);
01287   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);
01288   target_rot.Normalize(); // eliminates invalid rotation (0, 0, 0, 0)
01289   gazebo::math::Pose target_pose(target_pos,target_rot);
01290   gazebo::math::Vector3 target_pos_dot(req.model_state.twist.linear.x,req.model_state.twist.linear.y,req.model_state.twist.linear.z);
01291   gazebo::math::Vector3 target_rot_dot(req.model_state.twist.angular.x,req.model_state.twist.angular.y,req.model_state.twist.angular.z);
01292 
01293   gazebo::physics::ModelPtr model = world_->GetModel(req.model_state.model_name);
01294   if (!model)
01295   {
01296     ROS_ERROR("Updating ModelState: model [%s] does not exist",req.model_state.model_name.c_str());
01297     res.success = false;
01298     res.status_message = "SetModelState: model does not exist";
01299     return true;
01300   }
01301   else
01302   {
01303     gazebo::physics::LinkPtr relative_entity = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.model_state.reference_frame));
01304     if (relative_entity)
01305     {
01306       gazebo::math::Pose  frame_pose = relative_entity->GetWorldPose(); // - myBody->GetCoMPose();
01307       gazebo::math::Vector3 frame_pos = frame_pose.pos;
01308       gazebo::math::Quaternion frame_rot = frame_pose.rot;
01309 
01310       //std::cout << " debug : " << relative_entity->GetName() << " : " << frame_pose << " : " << target_pose << std::endl;
01311       //target_pose = frame_pose + target_pose; // seems buggy, use my own
01312       target_pose.pos = model->GetWorldPose().pos + frame_rot.RotateVector(target_pos);
01313       target_pose.rot = frame_rot * target_pose.rot;
01314 
01315       // Velocities should be commanded in the requested reference
01316       // frame, so we need to translate them to the world frame
01317       target_pos_dot = frame_rot.RotateVector(target_pos_dot);
01318       target_rot_dot = frame_rot.RotateVector(target_rot_dot);
01319     }
01321     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" )
01322     {
01323       ROS_DEBUG("Updating ModelState: reference frame is empty/world/map, usig inertial frame");
01324     }
01325     else
01326     {
01327       ROS_ERROR("Updating ModelState: for model[%s], specified reference frame entity [%s] does not exist",
01328                 req.model_state.model_name.c_str(),req.model_state.reference_frame.c_str());
01329       res.success = false;
01330       res.status_message = "SetModelState: specified reference frame entity does not exist";
01331       return true;
01332     }
01333 
01334     //ROS_ERROR("target state: %f %f %f",target_pose.pos.x,target_pose.pos.y,target_pose.pos.z);
01335     bool is_paused = world_->IsPaused();
01336     world_->SetPaused(true);
01337     model->SetWorldPose(target_pose);
01338     world_->SetPaused(is_paused);
01339     //gazebo::math::Pose p3d = model->GetWorldPose();
01340     //ROS_ERROR("model updated state: %f %f %f",p3d.pos.x,p3d.pos.y,p3d.pos.z);
01341 
01342     // set model velocity
01343     model->SetLinearVel(target_pos_dot);
01344     model->SetAngularVel(target_rot_dot);
01345 
01346     res.success = true;
01347     res.status_message = "SetModelState: set model state done";
01348     return true;
01349   }
01350 }
01351 
01352 void GazeboRosApiPlugin::updateModelState(const gazebo_msgs::ModelState::ConstPtr& model_state)
01353 {
01354   gazebo_msgs::SetModelState::Response res;
01355   gazebo_msgs::SetModelState::Request req;
01356   req.model_state = *model_state;
01357   /*bool success =*/ setModelState(req,res);
01358 }
01359 
01360 bool GazeboRosApiPlugin::applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req,
01361                                           gazebo_msgs::ApplyJointEffort::Response &res)
01362 {
01363   gazebo::physics::JointPtr joint;
01364   for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
01365   {
01366     joint = world_->GetModel(i)->GetJoint(req.joint_name);
01367     if (joint)
01368     {
01369       GazeboRosApiPlugin::ForceJointJob* fjj = new GazeboRosApiPlugin::ForceJointJob;
01370       fjj->joint = joint;
01371       fjj->force = req.effort;
01372       fjj->start_time = req.start_time;
01373       if (fjj->start_time < ros::Time(world_->GetSimTime().Double()))
01374         fjj->start_time = ros::Time(world_->GetSimTime().Double());
01375       fjj->duration = req.duration;
01376       lock_.lock();
01377       force_joint_jobs_.push_back(fjj);
01378       lock_.unlock();
01379 
01380       res.success = true;
01381       res.status_message = "ApplyJointEffort: effort set";
01382       return true;
01383     }
01384   }
01385 
01386   res.success = false;
01387   res.status_message = "ApplyJointEffort: joint not found";
01388   return true;
01389 }
01390 
01391 bool GazeboRosApiPlugin::resetSimulation(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01392 {
01393   world_->Reset();
01394   return true;
01395 }
01396 
01397 bool GazeboRosApiPlugin::resetWorld(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01398 {
01399   world_->ResetEntities(gazebo::physics::Base::MODEL);
01400   return true;
01401 }
01402 
01403 bool GazeboRosApiPlugin::pausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01404 {
01405   world_->SetPaused(true);
01406   return true;
01407 }
01408 
01409 bool GazeboRosApiPlugin::unpausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
01410 {
01411   world_->SetPaused(false);
01412   return true;
01413 }
01414 
01415 bool GazeboRosApiPlugin::clearJointForces(gazebo_msgs::JointRequest::Request &req,
01416                                           gazebo_msgs::JointRequest::Response &res)
01417 {
01418   return clearJointForces(req.joint_name);
01419 }
01420 bool GazeboRosApiPlugin::clearJointForces(std::string joint_name)
01421 {
01422   bool search = true;
01423   lock_.lock();
01424   while(search)
01425   {
01426     search = false;
01427     for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();++iter)
01428     {
01429       if ((*iter)->joint->GetName() == joint_name)
01430       {
01431         // found one, search through again
01432         search = true;
01433         delete (*iter);
01434         force_joint_jobs_.erase(iter);
01435         break;
01436       }
01437     }
01438   }
01439   lock_.unlock();
01440   return true;
01441 }
01442 
01443 bool GazeboRosApiPlugin::clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req,
01444                                            gazebo_msgs::BodyRequest::Response &res)
01445 {
01446   return clearBodyWrenches(req.body_name);
01447 }
01448 bool GazeboRosApiPlugin::clearBodyWrenches(std::string body_name)
01449 {
01450   bool search = true;
01451   lock_.lock();
01452   while(search)
01453   {
01454     search = false;
01455     for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();++iter)
01456     {
01457       //ROS_ERROR("search %s %s",(*iter)->body->GetScopedName().c_str(), body_name.c_str());
01458       if ((*iter)->body->GetScopedName() == body_name)
01459       {
01460         // found one, search through again
01461         search = true;
01462         delete (*iter);
01463         wrench_body_jobs_.erase(iter);
01464         break;
01465       }
01466     }
01467   }
01468   lock_.unlock();
01469   return true;
01470 }
01471 
01472 bool GazeboRosApiPlugin::setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req,
01473                                                gazebo_msgs::SetModelConfiguration::Response &res)
01474 {
01475   std::string gazebo_model_name = req.model_name;
01476 
01477   // search for model with name
01478   gazebo::physics::ModelPtr gazebo_model = world_->GetModel(req.model_name);
01479   if (!gazebo_model)
01480   {
01481     ROS_ERROR("SetModelConfiguration: model [%s] does not exist",gazebo_model_name.c_str());
01482     res.success = false;
01483     res.status_message = "SetModelConfiguration: model does not exist";
01484     return true;
01485   }
01486 
01487   if (req.joint_names.size() == req.joint_positions.size())
01488   {
01489     std::map<std::string, double> joint_position_map;
01490     for (unsigned int i = 0; i < req.joint_names.size(); i++)
01491     {
01492       joint_position_map[req.joint_names[i]] = req.joint_positions[i];
01493     }
01494 
01495     // make the service call to pause gazebo
01496     bool is_paused = world_->IsPaused();
01497     if (!is_paused) world_->SetPaused(true);
01498 
01499     gazebo_model->SetJointPositions(joint_position_map);
01500 
01501     // resume paused state before this call
01502     world_->SetPaused(is_paused);
01503 
01504     res.success = true;
01505     res.status_message = "SetModelConfiguration: success";
01506     return true;
01507   }
01508   else
01509   {
01510     res.success = false;
01511     res.status_message = "SetModelConfiguration: joint name and position list have different lengths";
01512     return true;
01513   }
01514 }
01515 
01516 bool GazeboRosApiPlugin::setLinkState(gazebo_msgs::SetLinkState::Request &req,
01517                                       gazebo_msgs::SetLinkState::Response &res)
01518 {
01519   gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_state.link_name));
01520   gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_state.reference_frame));
01521   if (!body)
01522   {
01523     ROS_ERROR("Updating LinkState: link [%s] does not exist",req.link_state.link_name.c_str());
01524     res.success = false;
01525     res.status_message = "SetLinkState: link does not exist";
01526     return true;
01527   }
01528 
01530   // get reference frame (body/model(link)) pose and
01531   // transform target pose to absolute world frame
01532   gazebo::math::Vector3 target_pos(req.link_state.pose.position.x,req.link_state.pose.position.y,req.link_state.pose.position.z);
01533   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);
01534   gazebo::math::Pose target_pose(target_pos,target_rot);
01535   gazebo::math::Vector3 target_linear_vel(req.link_state.twist.linear.x,req.link_state.twist.linear.y,req.link_state.twist.linear.z);
01536   gazebo::math::Vector3 target_angular_vel(req.link_state.twist.angular.x,req.link_state.twist.angular.y,req.link_state.twist.angular.z);
01537 
01538   if (frame)
01539   {
01540     gazebo::math::Pose  frame_pose = frame->GetWorldPose(); // - myBody->GetCoMPose();
01541     gazebo::math::Vector3 frame_pos = frame_pose.pos;
01542     gazebo::math::Quaternion frame_rot = frame_pose.rot;
01543 
01544     //std::cout << " debug : " << frame->GetName() << " : " << frame_pose << " : " << target_pose << std::endl;
01545     //target_pose = frame_pose + target_pose; // seems buggy, use my own
01546     target_pose.pos = frame_pos + frame_rot.RotateVector(target_pos);
01547     target_pose.rot = frame_rot * target_pose.rot;
01548 
01549     gazebo::math::Vector3 frame_linear_vel = frame->GetWorldLinearVel();
01550     gazebo::math::Vector3 frame_angular_vel = frame->GetWorldAngularVel();
01551     target_linear_vel -= frame_linear_vel;
01552     target_angular_vel -= frame_angular_vel;
01553   }
01554   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")
01555   {
01556     ROS_INFO("Updating LinkState: reference_frame is empty/world/map, using inertial frame");
01557   }
01558   else
01559   {
01560     ROS_ERROR("Updating LinkState: reference_frame is not a valid link name");
01561     res.success = false;
01562     res.status_message = "SetLinkState: failed";
01563     return true;
01564   }
01565 
01566   //std::cout << " debug : " << target_pose << std::endl;
01567   //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
01568 
01569   bool is_paused = world_->IsPaused();
01570   if (!is_paused) world_->SetPaused(true);
01571   body->SetWorldPose(target_pose);
01572   world_->SetPaused(is_paused);
01573 
01574   // set body velocity to desired twist
01575   body->SetLinearVel(target_linear_vel);
01576   body->SetAngularVel(target_angular_vel);
01577 
01578   res.success = true;
01579   res.status_message = "SetLinkState: success";
01580   return true;
01581 }
01582 
01583 void GazeboRosApiPlugin::updateLinkState(const gazebo_msgs::LinkState::ConstPtr& link_state)
01584 {
01585   gazebo_msgs::SetLinkState::Request req;
01586   gazebo_msgs::SetLinkState::Response res;
01587   req.link_state = *link_state;
01588   /*bool success = */ setLinkState(req,res);
01589 }
01590 
01591 void GazeboRosApiPlugin::transformWrench( gazebo::math::Vector3 &target_force, gazebo::math::Vector3 &target_torque,
01592                                           gazebo::math::Vector3 reference_force, gazebo::math::Vector3 reference_torque,
01593                                           gazebo::math::Pose target_to_reference )
01594 {
01595   // rotate force into target frame
01596   target_force = target_to_reference.rot.RotateVector(reference_force);
01597   // rotate torque into target frame
01598   target_torque = target_to_reference.rot.RotateVector(reference_torque);
01599 
01600   // target force is the refence force rotated by the target->reference transform
01601   target_torque = target_torque + target_to_reference.pos.Cross(target_force);
01602 }
01603 
01604 bool GazeboRosApiPlugin::applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req,
01605                                          gazebo_msgs::ApplyBodyWrench::Response &res)
01606 {
01607   gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.body_name));
01608   gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.reference_frame));
01609   if (!body)
01610   {
01611     ROS_ERROR("ApplyBodyWrench: body [%s] does not exist",req.body_name.c_str());
01612     res.success = false;
01613     res.status_message = "ApplyBodyWrench: body does not exist";
01614     return true;
01615   }
01616 
01617   // target wrench
01618   gazebo::math::Vector3 reference_force(req.wrench.force.x,req.wrench.force.y,req.wrench.force.z);
01619   gazebo::math::Vector3 reference_torque(req.wrench.torque.x,req.wrench.torque.y,req.wrench.torque.z);
01620   gazebo::math::Vector3 reference_point(req.reference_point.x,req.reference_point.y,req.reference_point.z);
01621 
01622   gazebo::math::Vector3 target_force;
01623   gazebo::math::Vector3 target_torque;
01624 
01627   reference_torque = reference_torque + reference_point.Cross(reference_force);
01628 
01630   if (frame)
01631   {
01632     // get reference frame (body/model(body)) pose and
01633     // transform target pose to absolute world frame
01634     // @todo: need to modify wrench (target force and torque by frame)
01635     //        transform wrench from reference_point in reference_frame
01636     //        into the reference frame of the body
01637     //        first, translate by reference point to the body frame
01638     gazebo::math::Pose target_to_reference = frame->GetWorldPose() - body->GetWorldPose();
01639     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]",
01640               body->GetWorldPose().pos.x,
01641               body->GetWorldPose().pos.y,
01642               body->GetWorldPose().pos.z,
01643               body->GetWorldPose().rot.GetAsEuler().x,
01644               body->GetWorldPose().rot.GetAsEuler().y,
01645               body->GetWorldPose().rot.GetAsEuler().z,
01646               frame->GetWorldPose().pos.x,
01647               frame->GetWorldPose().pos.y,
01648               frame->GetWorldPose().pos.z,
01649               frame->GetWorldPose().rot.GetAsEuler().x,
01650               frame->GetWorldPose().rot.GetAsEuler().y,
01651               frame->GetWorldPose().rot.GetAsEuler().z,
01652               target_to_reference.pos.x,
01653               target_to_reference.pos.y,
01654               target_to_reference.pos.z,
01655               target_to_reference.rot.GetAsEuler().x,
01656               target_to_reference.rot.GetAsEuler().y,
01657               target_to_reference.rot.GetAsEuler().z
01658               );
01659     transformWrench(target_force, target_torque, reference_force, reference_torque, target_to_reference);
01660     ROS_ERROR("wrench defined as [%s]:[%f %f %f, %f %f %f] --> applied as [%s]:[%f %f %f, %f %f %f]",
01661               frame->GetName().c_str(),
01662               reference_force.x,
01663               reference_force.y,
01664               reference_force.z,
01665               reference_torque.x,
01666               reference_torque.y,
01667               reference_torque.z,
01668               body->GetName().c_str(),
01669               target_force.x,
01670               target_force.y,
01671               target_force.z,
01672               target_torque.x,
01673               target_torque.y,
01674               target_torque.z
01675               );
01676 
01677   }
01678   else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
01679   {
01680     ROS_INFO("ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame");
01681     // FIXME: transfer to inertial frame
01682     gazebo::math::Pose target_to_reference = body->GetWorldPose();
01683     target_force = reference_force;
01684     target_torque = reference_torque;
01685 
01686   }
01687   else
01688   {
01689     ROS_ERROR("ApplyBodyWrench: reference_frame is not a valid link name");
01690     res.success = false;
01691     res.status_message = "ApplyBodyWrench: reference_frame not found";
01692     return true;
01693   }
01694 
01695   // apply wrench
01696   // schedule a job to do below at appropriate times:
01697   // body->SetForce(force)
01698   // body->SetTorque(torque)
01699   GazeboRosApiPlugin::WrenchBodyJob* wej = new GazeboRosApiPlugin::WrenchBodyJob;
01700   wej->body = body;
01701   wej->force = target_force;
01702   wej->torque = target_torque;
01703   wej->start_time = req.start_time;
01704   if (wej->start_time < ros::Time(world_->GetSimTime().Double()))
01705     wej->start_time = ros::Time(world_->GetSimTime().Double());
01706   wej->duration = req.duration;
01707   lock_.lock();
01708   wrench_body_jobs_.push_back(wej);
01709   lock_.unlock();
01710 
01711   res.success = true;
01712   res.status_message = "";
01713   return true;
01714 }
01715 
01716 bool GazeboRosApiPlugin::isURDF(std::string model_xml)
01717 {
01718   TiXmlDocument doc_in;
01719   doc_in.Parse(model_xml.c_str());
01720   if (doc_in.FirstChild("robot"))
01721     return true;
01722   else
01723     return false;
01724 }
01725 
01726 bool GazeboRosApiPlugin::isSDF(std::string model_xml)
01727 {
01728   // FIXME: very crude check
01729   TiXmlDocument doc_in;
01730   doc_in.Parse(model_xml.c_str());
01731   if (doc_in.FirstChild("gazebo") ||
01732       doc_in.FirstChild("sdf")) // sdf
01733     return true;
01734   else
01735     return false;
01736 }
01737 
01738 void GazeboRosApiPlugin::wrenchBodySchedulerSlot()
01739 {
01740   // MDMutex locks in case model is getting deleted, don't have to do this if we delete jobs first
01741   // boost::recursive_mutex::scoped_lock lock(*world->GetMDMutex());
01742   lock_.lock();
01743   for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();)
01744   {
01745     // check times and apply wrench if necessary
01746     if (ros::Time(world_->GetSimTime().Double()) >= (*iter)->start_time)
01747       if (ros::Time(world_->GetSimTime().Double()) <= (*iter)->start_time+(*iter)->duration ||
01748           (*iter)->duration.toSec() < 0.0)
01749       {
01750         if ((*iter)->body) // if body exists
01751         {
01752           (*iter)->body->SetForce((*iter)->force);
01753           (*iter)->body->SetTorque((*iter)->torque);
01754         }
01755         else
01756           (*iter)->duration.fromSec(0.0); // mark for delete
01757       }
01758 
01759     if (ros::Time(world_->GetSimTime().Double()) > (*iter)->start_time+(*iter)->duration &&
01760         (*iter)->duration.toSec() >= 0.0)
01761     {
01762       // remove from queue once expires
01763       delete (*iter);
01764       iter = wrench_body_jobs_.erase(iter);
01765     }
01766     else
01767       ++iter;
01768   }
01769   lock_.unlock();
01770 }
01771 
01772 void GazeboRosApiPlugin::forceJointSchedulerSlot()
01773 {
01774   // MDMutex locks in case model is getting deleted, don't have to do this if we delete jobs first
01775   // boost::recursive_mutex::scoped_lock lock(*world->GetMDMutex());
01776   lock_.lock();
01777   for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();)
01778   {
01779     // check times and apply force if necessary
01780     if (ros::Time(world_->GetSimTime().Double()) >= (*iter)->start_time)
01781       if (ros::Time(world_->GetSimTime().Double()) <= (*iter)->start_time+(*iter)->duration ||
01782           (*iter)->duration.toSec() < 0.0)
01783       {
01784         if ((*iter)->joint) // if joint exists
01785           (*iter)->joint->SetForce(0,(*iter)->force);
01786         else
01787           (*iter)->duration.fromSec(0.0); // mark for delete
01788       }
01789 
01790     if (ros::Time(world_->GetSimTime().Double()) > (*iter)->start_time+(*iter)->duration &&
01791         (*iter)->duration.toSec() >= 0.0)
01792     {
01793       // remove from queue once expires
01794       iter = force_joint_jobs_.erase(iter);
01795     }
01796     else
01797       ++iter;
01798   }
01799   lock_.unlock();
01800 }
01801 
01802 void GazeboRosApiPlugin::publishSimTime(const boost::shared_ptr<gazebo::msgs::WorldStatistics const> &msg)
01803 {
01804   ROS_ERROR("CLOCK2");
01805   gazebo::common::Time sim_time = world_->GetSimTime();
01806   if (pub_clock_frequency_ > 0 && (sim_time - last_pub_clock_time_).Double() < 1.0/pub_clock_frequency_)
01807     return;
01808 
01809   gazebo::common::Time currentTime = gazebo::msgs::Convert( msg->sim_time() );
01810   rosgraph_msgs::Clock ros_time_;
01811   ros_time_.clock.fromSec(currentTime.Double());
01812   //  publish time to ros
01813   last_pub_clock_time_ = sim_time;
01814   pub_clock_.publish(ros_time_);
01815 }
01816 void GazeboRosApiPlugin::publishSimTime()
01817 {
01818   gazebo::common::Time sim_time = world_->GetSimTime();
01819   if (pub_clock_frequency_ > 0 && (sim_time - last_pub_clock_time_).Double() < 1.0/pub_clock_frequency_)
01820     return;
01821 
01822   gazebo::common::Time currentTime = world_->GetSimTime();
01823   rosgraph_msgs::Clock ros_time_;
01824   ros_time_.clock.fromSec(currentTime.Double());
01825   //  publish time to ros
01826   last_pub_clock_time_ = sim_time;
01827   pub_clock_.publish(ros_time_);
01828 }
01829 
01830 void GazeboRosApiPlugin::publishLinkStates()
01831 {
01832   gazebo_msgs::LinkStates link_states;
01833 
01834   // fill link_states
01835   for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
01836   {
01837     gazebo::physics::ModelPtr model = world_->GetModel(i);
01838 
01839     for (unsigned int j = 0 ; j < model->GetChildCount(); j ++)
01840     {
01841       gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(j));
01842 
01843       if (body)
01844       {
01845         link_states.name.push_back(body->GetScopedName());
01846         geometry_msgs::Pose pose;
01847         gazebo::math::Pose  body_pose = body->GetWorldPose(); // - myBody->GetCoMPose();
01848         gazebo::math::Vector3 pos = body_pose.pos;
01849         gazebo::math::Quaternion rot = body_pose.rot;
01850         pose.position.x = pos.x;
01851         pose.position.y = pos.y;
01852         pose.position.z = pos.z;
01853         pose.orientation.w = rot.w;
01854         pose.orientation.x = rot.x;
01855         pose.orientation.y = rot.y;
01856         pose.orientation.z = rot.z;
01857         link_states.pose.push_back(pose);
01858         gazebo::math::Vector3 linear_vel  = body->GetWorldLinearVel();
01859         gazebo::math::Vector3 angular_vel = body->GetWorldAngularVel();
01860         geometry_msgs::Twist twist;
01861         twist.linear.x = linear_vel.x;
01862         twist.linear.y = linear_vel.y;
01863         twist.linear.z = linear_vel.z;
01864         twist.angular.x = angular_vel.x;
01865         twist.angular.y = angular_vel.y;
01866         twist.angular.z = angular_vel.z;
01867         link_states.twist.push_back(twist);
01868       }
01869     }
01870   }
01871 
01872   pub_link_states_.publish(link_states);
01873 }
01874 
01875 void GazeboRosApiPlugin::publishModelStates()
01876 {
01877   gazebo_msgs::ModelStates model_states;
01878 
01879   // fill model_states
01880   for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
01881   {
01882     gazebo::physics::ModelPtr model = world_->GetModel(i);
01883     model_states.name.push_back(model->GetName());
01884     geometry_msgs::Pose pose;
01885     gazebo::math::Pose  model_pose = model->GetWorldPose(); // - myBody->GetCoMPose();
01886     gazebo::math::Vector3 pos = model_pose.pos;
01887     gazebo::math::Quaternion rot = model_pose.rot;
01888     pose.position.x = pos.x;
01889     pose.position.y = pos.y;
01890     pose.position.z = pos.z;
01891     pose.orientation.w = rot.w;
01892     pose.orientation.x = rot.x;
01893     pose.orientation.y = rot.y;
01894     pose.orientation.z = rot.z;
01895     model_states.pose.push_back(pose);
01896     gazebo::math::Vector3 linear_vel  = model->GetWorldLinearVel();
01897     gazebo::math::Vector3 angular_vel = model->GetWorldAngularVel();
01898     geometry_msgs::Twist twist;
01899     twist.linear.x = linear_vel.x;
01900     twist.linear.y = linear_vel.y;
01901     twist.linear.z = linear_vel.z;
01902     twist.angular.x = angular_vel.x;
01903     twist.angular.y = angular_vel.y;
01904     twist.angular.z = angular_vel.z;
01905     model_states.twist.push_back(twist);
01906   }
01907   pub_model_states_.publish(model_states);
01908 }
01909 
01910 void GazeboRosApiPlugin::physicsReconfigureCallback(gazebo_ros::PhysicsConfig &config, uint32_t level)
01911 {
01912   if (!physics_reconfigure_initialized_)
01913   {
01914     gazebo_msgs::GetPhysicsProperties srv;
01915     physics_reconfigure_get_client_.call(srv);
01916 
01917     config.time_step                   = srv.response.time_step;
01918     config.max_update_rate             = srv.response.max_update_rate;
01919     config.gravity_x                   = srv.response.gravity.x;
01920     config.gravity_y                   = srv.response.gravity.y;
01921     config.gravity_z                   = srv.response.gravity.z;
01922     config.auto_disable_bodies         = srv.response.ode_config.auto_disable_bodies;
01923     config.sor_pgs_precon_iters        = srv.response.ode_config.sor_pgs_precon_iters;
01924     config.sor_pgs_iters               = srv.response.ode_config.sor_pgs_iters;
01925     config.sor_pgs_rms_error_tol       = srv.response.ode_config.sor_pgs_rms_error_tol;
01926     config.sor_pgs_w                   = srv.response.ode_config.sor_pgs_w;
01927     config.contact_surface_layer       = srv.response.ode_config.contact_surface_layer;
01928     config.contact_max_correcting_vel  = srv.response.ode_config.contact_max_correcting_vel;
01929     config.cfm                         = srv.response.ode_config.cfm;
01930     config.erp                         = srv.response.ode_config.erp;
01931     config.max_contacts                = srv.response.ode_config.max_contacts;
01932     physics_reconfigure_initialized_ = true;
01933   }
01934   else
01935   {
01936     bool changed = false;
01937     gazebo_msgs::GetPhysicsProperties srv;
01938     physics_reconfigure_get_client_.call(srv);
01939 
01940     // check for changes
01941     if (config.time_step                      != srv.response.time_step)                                 changed = true;
01942     if (config.max_update_rate                != srv.response.max_update_rate)                           changed = true;
01943     if (config.gravity_x                      != srv.response.gravity.x)                                 changed = true;
01944     if (config.gravity_y                      != srv.response.gravity.y)                                 changed = true;
01945     if (config.gravity_z                      != srv.response.gravity.z)                                 changed = true;
01946     if (config.auto_disable_bodies            != srv.response.ode_config.auto_disable_bodies)            changed = true;
01947     if ((uint32_t)config.sor_pgs_precon_iters != srv.response.ode_config.sor_pgs_precon_iters)           changed = true;
01948     if ((uint32_t)config.sor_pgs_iters        != srv.response.ode_config.sor_pgs_iters)                  changed = true;
01949     if (config.sor_pgs_rms_error_tol          != srv.response.ode_config.sor_pgs_rms_error_tol)          changed = true;
01950     if (config.sor_pgs_w                      != srv.response.ode_config.sor_pgs_w)                      changed = true;
01951     if (config.contact_surface_layer          != srv.response.ode_config.contact_surface_layer)          changed = true;
01952     if (config.contact_max_correcting_vel     != srv.response.ode_config.contact_max_correcting_vel)     changed = true;
01953     if (config.cfm                            != srv.response.ode_config.cfm)                            changed = true;
01954     if (config.erp                            != srv.response.ode_config.erp)                            changed = true;
01955     if ((uint32_t)config.max_contacts         != srv.response.ode_config.max_contacts)                   changed = true;
01956 
01957     if (changed)
01958     {
01959       // pause simulation if requested
01960       gazebo_msgs::SetPhysicsProperties srv;
01961       srv.request.time_step                             = config.time_step                   ;
01962       srv.request.max_update_rate                       = config.max_update_rate             ;
01963       srv.request.gravity.x                             = config.gravity_x                   ;
01964       srv.request.gravity.y                             = config.gravity_y                   ;
01965       srv.request.gravity.z                             = config.gravity_z                   ;
01966       srv.request.ode_config.auto_disable_bodies        = config.auto_disable_bodies         ;
01967       srv.request.ode_config.sor_pgs_precon_iters       = config.sor_pgs_precon_iters        ;
01968       srv.request.ode_config.sor_pgs_iters              = config.sor_pgs_iters               ;
01969       srv.request.ode_config.sor_pgs_rms_error_tol      = config.sor_pgs_rms_error_tol       ;
01970       srv.request.ode_config.sor_pgs_w                  = config.sor_pgs_w                   ;
01971       srv.request.ode_config.contact_surface_layer      = config.contact_surface_layer       ;
01972       srv.request.ode_config.contact_max_correcting_vel = config.contact_max_correcting_vel  ;
01973       srv.request.ode_config.cfm                        = config.cfm                         ;
01974       srv.request.ode_config.erp                        = config.erp                         ;
01975       srv.request.ode_config.max_contacts               = config.max_contacts                ;
01976       physics_reconfigure_set_client_.call(srv);
01977       ROS_INFO("physics dynamics reconfigure update complete");
01978     }
01979     ROS_INFO("physics dynamics reconfigure complete");
01980   }
01981 }
01982 
01983 void GazeboRosApiPlugin::physicsReconfigureThread()
01984 {
01985   physics_reconfigure_set_client_ = nh_->serviceClient<gazebo_msgs::SetPhysicsProperties>("/gazebo/set_physics_properties");
01986   physics_reconfigure_get_client_ = nh_->serviceClient<gazebo_msgs::GetPhysicsProperties>("/gazebo/get_physics_properties");
01987 
01988   // Wait until the rest of this plugin is loaded and the services are being offered
01989   physics_reconfigure_set_client_.waitForExistence();
01990   physics_reconfigure_get_client_.waitForExistence();
01991 
01992   physics_reconfigure_srv_.reset(new dynamic_reconfigure::Server<gazebo_ros::PhysicsConfig>());
01993 
01994   physics_reconfigure_callback_ = boost::bind(&GazeboRosApiPlugin::physicsReconfigureCallback, this, _1, _2);
01995   physics_reconfigure_srv_->setCallback(physics_reconfigure_callback_);
01996 
01997   ROS_INFO("Physics dynamic reconfigure ready.");
01998 }
01999 
02000 void GazeboRosApiPlugin::stripXmlDeclaration(std::string &model_xml)
02001 {
02002   // incoming robot model string is a string containing a Gazebo Model XML
02006   std::string open_bracket("<?");
02007   std::string close_bracket("?>");
02008   size_t pos1 = model_xml.find(open_bracket,0);
02009   size_t pos2 = model_xml.find(close_bracket,0);
02010   if (pos1 != std::string::npos && pos2 != std::string::npos)
02011     model_xml.replace(pos1,pos2-pos1+2,std::string(""));
02012 }
02013 
02014 void GazeboRosApiPlugin::updateSDFAttributes(TiXmlDocument &gazebo_model_xml, std::string model_name,
02015                                              gazebo::math::Vector3 initial_xyz, gazebo::math::Quaternion initial_q)
02016 {
02017   // This function can handle both regular SDF files and <include> SDFs that are used with the
02018   // Gazebo Model Database
02019 
02020   TiXmlElement* pose_element; // This is used by both reguar and database SDFs
02021 
02022   // Check SDF for requires SDF element
02023   TiXmlElement* gazebo_tixml = gazebo_model_xml.FirstChildElement("sdf");
02024   if (!gazebo_tixml)
02025   {
02026     ROS_WARN("Could not find <sdf> element in sdf, so name and initial position cannot be applied");
02027     return;
02028   }
02029 
02030   // Check SDF for optional model element. May not have one
02031   TiXmlElement* model_tixml = gazebo_tixml->FirstChildElement("model");
02032   if (model_tixml)
02033   {
02034     // Update model name
02035     if (model_tixml->Attribute("name") != NULL)
02036     {
02037       // removing old model name
02038       model_tixml->RemoveAttribute("name");
02039     }
02040     // replace with user specified name
02041     model_tixml->SetAttribute("name",model_name);
02042   }
02043   else
02044   {
02045     // Check SDF for world element
02046     TiXmlElement* world_tixml = gazebo_tixml->FirstChildElement("world");
02047     if (!world_tixml)
02048     {
02049       ROS_WARN("Could not find <model> or <world> element in sdf, so name and initial position cannot be applied");
02050       return;
02051     }
02052     // If not <model> element, check SDF for required include element
02053     model_tixml = world_tixml->FirstChildElement("include");
02054     if (!model_tixml)
02055     {
02056       ROS_WARN("Could not find <include> element in sdf, so name and initial position cannot be applied");
02057       return;
02058     }
02059 
02060     // Check for name element
02061     TiXmlElement* name_tixml = model_tixml->FirstChildElement("name");
02062     if (!name_tixml)
02063     {
02064       // Create the name element
02065       name_tixml = new TiXmlElement("name");
02066       model_tixml->LinkEndChild(name_tixml);
02067     }
02068 
02069     // Set the text within the name element
02070     TiXmlText* text = new TiXmlText(model_name);
02071     name_tixml->LinkEndChild( text );
02072   }
02073 
02074 
02075   // Check for the pose element
02076   pose_element = model_tixml->FirstChildElement("pose");
02077   gazebo::math::Pose model_pose;
02078 
02079   // Create the pose element if it doesn't exist
02080   // Remove it if it exists, since we are inserting a new one
02081   if (pose_element)
02082   {
02083     // save pose_element in math::Pose and remove child
02084     model_pose = this->parsePose(pose_element->GetText());
02085     model_tixml->RemoveChild(pose_element);
02086   }
02087 
02088   // Set and link the pose element after adding initial pose
02089   {
02090     // add pose_element Pose to initial pose
02091     gazebo::math::Pose new_model_pose = model_pose + gazebo::math::Pose(initial_xyz, initial_q);
02092 
02093     // Create the string of 6 numbers
02094     std::ostringstream pose_stream;
02095     gazebo::math::Vector3 model_rpy = new_model_pose.rot.GetAsEuler(); // convert to Euler angles for Gazebo XML
02096     pose_stream << new_model_pose.pos.x << " " << new_model_pose.pos.y << " " << new_model_pose.pos.z << " "
02097                 << model_rpy.x << " " << model_rpy.y << " " << model_rpy.z;
02098 
02099     // Add value to pose element
02100     TiXmlText* text = new TiXmlText(pose_stream.str());
02101     TiXmlElement* new_pose_element = new TiXmlElement("pose");
02102     new_pose_element->LinkEndChild(text);
02103     model_tixml->LinkEndChild(new_pose_element);
02104   }
02105 }
02106 
02107 gazebo::math::Pose GazeboRosApiPlugin::parsePose(const std::string &str)
02108 {
02109   std::vector<std::string> pieces;
02110   std::vector<double> vals;
02111 
02112   boost::split(pieces, str, boost::is_any_of(" "));
02113   for (unsigned int i = 0; i < pieces.size(); ++i)
02114   {
02115     if (pieces[i] != "")
02116     {
02117       try
02118       {
02119         vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
02120       }
02121       catch(boost::bad_lexical_cast &e)
02122       {
02123         sdferr << "xml key [" << str
02124           << "][" << i << "] value [" << pieces[i]
02125           << "] is not a valid double from a 3-tuple\n";
02126         return gazebo::math::Pose();
02127       }
02128     }
02129   }
02130 
02131   if (vals.size() == 6)
02132     return gazebo::math::Pose(vals[0], vals[1], vals[2], vals[3], vals[4], vals[5]);
02133   else
02134   {
02135     ROS_ERROR("Beware: failed to parse string [%s] as gazebo::math::Pose, returning zeros.", str.c_str());
02136     return gazebo::math::Pose();
02137   }
02138 }
02139 
02140 gazebo::math::Vector3 GazeboRosApiPlugin::parseVector3(const std::string &str)
02141 {
02142   std::vector<std::string> pieces;
02143   std::vector<double> vals;
02144 
02145   boost::split(pieces, str, boost::is_any_of(" "));
02146   for (unsigned int i = 0; i < pieces.size(); ++i)
02147   {
02148     if (pieces[i] != "")
02149     {
02150       try
02151       {
02152         vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
02153       }
02154       catch(boost::bad_lexical_cast &e)
02155       {
02156         sdferr << "xml key [" << str
02157           << "][" << i << "] value [" << pieces[i]
02158           << "] is not a valid double from a 3-tuple\n";
02159         return gazebo::math::Vector3();
02160       }
02161     }
02162   }
02163 
02164   if (vals.size() == 3)
02165     return gazebo::math::Vector3(vals[0], vals[1], vals[2]);
02166   else
02167   {
02168     ROS_ERROR("Beware: failed to parse string [%s] as gazebo::math::Vector3, returning zeros.", str.c_str());
02169     return gazebo::math::Vector3();
02170   }
02171 }
02172 
02173 void GazeboRosApiPlugin::updateURDFModelPose(TiXmlDocument &gazebo_model_xml, gazebo::math::Vector3 initial_xyz, gazebo::math::Quaternion initial_q)
02174 {
02175   TiXmlElement* model_tixml = (gazebo_model_xml.FirstChildElement("robot"));
02176   if (model_tixml)
02177   {
02178     // replace initial pose of robot
02179     // find first instance of xyz and rpy, replace with initial pose
02180     TiXmlElement* origin_key = model_tixml->FirstChildElement("origin");
02181 
02182     if (!origin_key)
02183     {
02184       origin_key = new TiXmlElement("origin");
02185       model_tixml->LinkEndChild(origin_key);
02186     }
02187 
02188     gazebo::math::Vector3 xyz;
02189     gazebo::math::Vector3 rpy;
02190     if (origin_key->Attribute("xyz"))
02191     {
02192       xyz = this->parseVector3(origin_key->Attribute("xyz"));
02193       origin_key->RemoveAttribute("xyz");
02194     }
02195     if (origin_key->Attribute("rpy"))
02196     {
02197       rpy = this->parseVector3(origin_key->Attribute("rpy"));
02198       origin_key->RemoveAttribute("rpy");
02199     }
02200 
02201     // add xyz, rpy to initial pose
02202     gazebo::math::Pose model_pose = gazebo::math::Pose(xyz, rpy) + gazebo::math::Pose(initial_xyz, initial_q);
02203 
02204     std::ostringstream xyz_stream;
02205     xyz_stream << model_pose.pos.x << " " << model_pose.pos.y << " " << model_pose.pos.z;
02206 
02207     std::ostringstream rpy_stream;
02208     gazebo::math::Vector3 model_rpy = model_pose.rot.GetAsEuler(); // convert to Euler angles for Gazebo XML
02209     rpy_stream << model_rpy.x << " " << model_rpy.y << " " << model_rpy.z;
02210 
02211     origin_key->SetAttribute("xyz",xyz_stream.str());
02212     origin_key->SetAttribute("rpy",rpy_stream.str());
02213   }
02214   else
02215     ROS_WARN("could not find <model> element in sdf, so name and initial position is not applied");
02216 }
02217 
02218 void GazeboRosApiPlugin::updateURDFName(TiXmlDocument &gazebo_model_xml, std::string model_name)
02219 {
02220   TiXmlElement* model_tixml = gazebo_model_xml.FirstChildElement("robot");
02221   // replace model name if one is specified by the user
02222   if (model_tixml)
02223   {
02224     if (model_tixml->Attribute("name") != NULL)
02225     {
02226       // removing old model name
02227       model_tixml->RemoveAttribute("name");
02228     }
02229     // replace with user specified name
02230     model_tixml->SetAttribute("name",model_name);
02231   }
02232   else
02233     ROS_WARN("could not find <robot> element in URDF, name not replaced");
02234 }
02235 
02236 void GazeboRosApiPlugin::walkChildAddRobotNamespace(TiXmlNode* robot_xml)
02237 {
02238   TiXmlNode* child = 0;
02239   child = robot_xml->IterateChildren(child);
02240   while (child != NULL)
02241   {
02242     if (child->ValueStr().find(std::string("plugin")) == 0)
02243     {
02244       if (child->FirstChildElement("robotNamespace") == NULL)
02245       {
02246         TiXmlElement* child_elem = child->ToElement()->FirstChildElement("robotNamespace");
02247         while (child_elem)
02248         {
02249           child->ToElement()->RemoveChild(child_elem);
02250           child_elem = child->ToElement()->FirstChildElement("robotNamespace");
02251         }
02252         TiXmlElement* key = new TiXmlElement("robotNamespace");
02253         TiXmlText* val = new TiXmlText(robot_namespace_);
02254         key->LinkEndChild(val);
02255         child->ToElement()->LinkEndChild(key);
02256       }
02257     }
02258     walkChildAddRobotNamespace(child);
02259     child = robot_xml->IterateChildren(child);
02260   }
02261 }
02262 
02263 bool GazeboRosApiPlugin::spawnAndConform(TiXmlDocument &gazebo_model_xml, std::string model_name,
02264                                          gazebo_msgs::SpawnModel::Response &res)
02265 {
02266   // push to factory iface
02267   std::ostringstream stream;
02268   stream << gazebo_model_xml;
02269   std::string gazebo_model_xml_string = stream.str();
02270   ROS_DEBUG("Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
02271 
02272   // publish to factory topic
02273   gazebo::msgs::Factory msg;
02274   gazebo::msgs::Init(msg, "spawn_model");
02275   msg.set_sdf( gazebo_model_xml_string );
02276 
02277   //ROS_ERROR("attempting to spawn model name [%s] [%s]", model_name.c_str(),gazebo_model_xml_string.c_str());
02278 
02279   // FIXME: should use entity_info or add lock to World::receiveMutex
02280   // looking for Model to see if it exists already
02281   gazebo::msgs::Request *entity_info_msg = gazebo::msgs::CreateRequest("entity_info", model_name);
02282   request_pub_->Publish(*entity_info_msg,true);
02283   // todo: should wait for response response_sub_, check to see that if _msg->response == "nonexistant"
02284 
02285   gazebo::physics::ModelPtr model = world_->GetModel(model_name);
02286   if (model)
02287   {
02288     ROS_ERROR("SpawnModel: Failure - model name %s already exist.",model_name.c_str());
02289     res.success = false;
02290     res.status_message = "SpawnModel: Failure - model already exists.";
02291     return true;
02292   }
02293 
02294   // Publish the factory message
02295   factory_pub_->Publish(msg);
02298 
02300   ros::Duration model_spawn_timeout(10.0);
02301   ros::Time timeout = ros::Time::now() + model_spawn_timeout;
02302 
02303   while (ros::ok())
02304   {
02305     if (ros::Time::now() > timeout)
02306     {
02307       res.success = false;
02308       res.status_message = std::string("SpawnModel: Model pushed to spawn queue, but spawn service")
02309         + std::string(" timed out waiting for model to appear in simulation under the name ")
02310         + model_name;
02311       return true;
02312     }
02313 
02314     {
02315       //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
02316       if (world_->GetModel(model_name))
02317         break;
02318     }
02319 
02320     ROS_DEBUG_STREAM_ONCE_NAMED("api_plugin","Waiting for " << timeout - ros::Time::now()
02321       << " for model " << model_name << " to spawn");
02322 
02323     usleep(2000);
02324   }
02325 
02326   // set result
02327   res.success = true;
02328   res.status_message = std::string("SpawnModel: Successfully spawned model");
02329   return true;
02330 }
02331 
02332 // Register this plugin with the simulator
02333 GZ_REGISTER_SYSTEM_PLUGIN(GazeboRosApiPlugin)
02334 }
02335 


gazebo_ros
Author(s): John Hsu, Nate Koenig, Dave Coleman
autogenerated on Thu Feb 23 2017 03:43:18