gazebo_ros_api_plugin.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 /* Desc: External interfaces for Gazebo
19  * Author: Nate Koenig, John Hsu, Dave Coleman
20  * Date: Jun 10 2013
21  */
22 
23 #include <gazebo/common/Events.hh>
24 #include <gazebo/gazebo_config.h>
26 
27 namespace gazebo
28 {
29 
31  physics_reconfigure_initialized_(false),
32  world_created_(false),
33  stop_(false),
34  plugin_loaded_(false),
35  pub_link_states_connection_count_(0),
36  pub_model_states_connection_count_(0),
37  pub_clock_frequency_(0),
38  enable_ros_network_(true)
39 {
40  robot_namespace_.clear();
41 }
42 
44 {
45  ROS_DEBUG_STREAM_NAMED("api_plugin","GazeboRosApiPlugin Deconstructor start");
46 
47  // Unload the sigint event
48  sigint_event_.reset();
49  ROS_DEBUG_STREAM_NAMED("api_plugin","After sigint_event unload");
50 
51  // Don't attempt to unload this plugin if it was never loaded in the Load() function
52  if(!plugin_loaded_)
53  {
54  ROS_DEBUG_STREAM_NAMED("api_plugin","Deconstructor skipped because never loaded");
55  return;
56  }
57 
58  // Disconnect slots
60  wrench_update_event_.reset();
61  force_update_event_.reset();
62  time_update_event_.reset();
63  ROS_DEBUG_STREAM_NAMED("api_plugin","Slots disconnected");
64 
65  if (pub_link_states_connection_count_ > 0) // disconnect if there are subscribers on exit
66  pub_link_states_event_.reset();
67  if (pub_model_states_connection_count_ > 0) // disconnect if there are subscribers on exit
69  ROS_DEBUG_STREAM_NAMED("api_plugin","Disconnected World Updates");
70 
71  // Stop the multi threaded ROS spinner
72  async_ros_spin_->stop();
73  ROS_DEBUG_STREAM_NAMED("api_plugin","Async ROS Spin Stopped");
74 
75  // Shutdown the ROS node
76  nh_->shutdown();
77  ROS_DEBUG_STREAM_NAMED("api_plugin","Node Handle Shutdown");
78 
79  // Shutdown ROS queue
81  ROS_DEBUG_STREAM_NAMED("api_plugin","Callback Queue Joined");
82 
83  // Physics Dynamic Reconfigure
85  ROS_DEBUG_STREAM_NAMED("api_plugin","Physics reconfigure joined");
86 
87  // Delete Force and Wrench Jobs
88  lock_.lock();
89  for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();)
90  {
91  delete (*iter);
92  iter = force_joint_jobs_.erase(iter);
93  }
94  force_joint_jobs_.clear();
95  ROS_DEBUG_STREAM_NAMED("api_plugin","ForceJointJobs deleted");
96  for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();)
97  {
98  delete (*iter);
99  iter = wrench_body_jobs_.erase(iter);
100  }
101  wrench_body_jobs_.clear();
102  lock_.unlock();
103  ROS_DEBUG_STREAM_NAMED("api_plugin","WrenchBodyJobs deleted");
104 
105  ROS_DEBUG_STREAM_NAMED("api_plugin","Unloaded");
106 }
107 
109 {
110  ROS_DEBUG_STREAM_NAMED("api_plugin","shutdownSignal() recieved");
111  stop_ = true;
112 }
113 
114 void GazeboRosApiPlugin::Load(int argc, char** argv)
115 {
116  ROS_DEBUG_STREAM_NAMED("api_plugin","Load");
117 
118  // connect to sigint event
119  sigint_event_ = gazebo::event::Events::ConnectSigInt(boost::bind(&GazeboRosApiPlugin::shutdownSignal,this));
120 
121  // setup ros related
122  if (!ros::isInitialized())
123  ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler);
124  else
125  ROS_ERROR_NAMED("api_plugin", "Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
126 
127  // check if the ros master is available - required
128  while(!ros::master::check())
129  {
130  ROS_WARN_STREAM_NAMED("api_plugin","No ROS master - start roscore to continue...");
131  // wait 0.5 second
132  usleep(500*1000); // can't use ROS Time here b/c node handle is not yet initialized
133 
134  if(stop_)
135  {
136  ROS_WARN_STREAM_NAMED("api_plugin","Canceled loading Gazebo ROS API plugin by sigint event");
137  return;
138  }
139  }
140 
141  nh_.reset(new ros::NodeHandle("~")); // advertise topics and services in this node's namespace
142 
143  // Built-in multi-threaded ROS spinning
144  async_ros_spin_.reset(new ros::AsyncSpinner(0)); // will use a thread for each CPU core
145  async_ros_spin_->start();
146 
148  gazebo_callback_queue_thread_.reset(new boost::thread( &GazeboRosApiPlugin::gazeboQueueThread, this) );
149 
151  physics_reconfigure_thread_.reset(new boost::thread(boost::bind(&GazeboRosApiPlugin::physicsReconfigureThread, this)));
152 
153  // below needs the world to be created first
154  load_gazebo_ros_api_plugin_event_ = gazebo::event::Events::ConnectWorldCreated(boost::bind(&GazeboRosApiPlugin::loadGazeboRosApiPlugin,this,_1));
155 
156  nh_->getParam("enable_ros_network", enable_ros_network_);
157 
158  plugin_loaded_ = true;
159  ROS_INFO_NAMED("api_plugin", "Finished loading Gazebo ROS API Plugin.");
160 }
161 
162 void GazeboRosApiPlugin::loadGazeboRosApiPlugin(std::string world_name)
163 {
164  // make sure things are only called once
165  lock_.lock();
166  if (world_created_)
167  {
168  lock_.unlock();
169  return;
170  }
171 
172  // set flag to true and load this plugin
173  world_created_ = true;
174  lock_.unlock();
175 
176  world_ = gazebo::physics::get_world(world_name);
177  if (!world_)
178  {
179  //ROS_ERROR_NAMED("api_plugin", "world name: [%s]",world->Name().c_str());
180  // connect helper function to signal for scheduling torque/forces, etc
181  ROS_FATAL_NAMED("api_plugin", "cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
182  return;
183  }
184 
185  gazebonode_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
186  gazebonode_->Init(world_name);
187  //stat_sub_ = gazebonode_->Subscribe("~/world_stats", &GazeboRosApiPlugin::publishSimTime, this); // TODO: does not work in server plugin?
188  factory_pub_ = gazebonode_->Advertise<gazebo::msgs::Factory>("~/factory");
189  factory_light_pub_ = gazebonode_->Advertise<gazebo::msgs::Light>("~/factory/light");
190  light_modify_pub_ = gazebonode_->Advertise<gazebo::msgs::Light>("~/light/modify");
191  request_pub_ = gazebonode_->Advertise<gazebo::msgs::Request>("~/request");
192  response_sub_ = gazebonode_->Subscribe("~/response",&GazeboRosApiPlugin::onResponse, this);
193 
194  // reset topic connection counts
197 
201 
202  // Manage clock for simulated ros time
203  pub_clock_ = nh_->advertise<rosgraph_msgs::Clock>("/clock",10);
204  // set param for use_sim_time if not set by user already
205  if(!(nh_->hasParam("/use_sim_time")))
206  nh_->setParam("/use_sim_time", true);
207 
208  nh_->getParam("pub_clock_frequency", pub_clock_frequency_);
209 #if GAZEBO_MAJOR_VERSION >= 8
210  last_pub_clock_time_ = world_->SimTime();
211 #else
212  last_pub_clock_time_ = world_->GetSimTime();
213 #endif
214 
215  // hooks for applying forces, publishing simtime on /clock
216  wrench_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::wrenchBodySchedulerSlot,this));
217  force_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::forceJointSchedulerSlot,this));
218  time_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishSimTime,this));
219 }
220 
221 void GazeboRosApiPlugin::onResponse(ConstResponsePtr &response)
222 {
223 
224 }
225 
227 {
228  static const double timeout = 0.001;
229  while (nh_->ok())
230  {
232  }
233 }
234 
236 {
237  if (! enable_ros_network_)
238  {
239  ROS_INFO_NAMED("api_plugin", "ROS gazebo topics/services are disabled");
240  return;
241  }
242 
243  // publish clock for simulated ros time
244  pub_clock_ = nh_->advertise<rosgraph_msgs::Clock>("/clock",10);
245 
246  // Advertise spawn services on the custom queue
247  std::string spawn_sdf_model_service_name("spawn_sdf_model");
248  ros::AdvertiseServiceOptions spawn_sdf_model_aso =
249  ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
250  spawn_sdf_model_service_name,
251  boost::bind(&GazeboRosApiPlugin::spawnSDFModel,this,_1,_2),
253  spawn_sdf_model_service_ = nh_->advertiseService(spawn_sdf_model_aso);
254 
255  // Advertise spawn services on the custom queue
256  std::string spawn_urdf_model_service_name("spawn_urdf_model");
257  ros::AdvertiseServiceOptions spawn_urdf_model_aso =
258  ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
259  spawn_urdf_model_service_name,
260  boost::bind(&GazeboRosApiPlugin::spawnURDFModel,this,_1,_2),
262  spawn_urdf_model_service_ = nh_->advertiseService(spawn_urdf_model_aso);
263 
264  // Advertise delete services on the custom queue
265  std::string delete_model_service_name("delete_model");
266  ros::AdvertiseServiceOptions delete_aso =
267  ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
268  delete_model_service_name,
269  boost::bind(&GazeboRosApiPlugin::deleteModel,this,_1,_2),
271  delete_model_service_ = nh_->advertiseService(delete_aso);
272 
273  // Advertise delete service for lights on the custom queue
274  std::string delete_light_service_name("delete_light");
275  ros::AdvertiseServiceOptions delete_light_aso =
276  ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteLight>(
277  delete_light_service_name,
278  boost::bind(&GazeboRosApiPlugin::deleteLight,this,_1,_2),
280  delete_light_service_ = nh_->advertiseService(delete_light_aso);
281 
282  // Advertise more services on the custom queue
283  std::string get_model_properties_service_name("get_model_properties");
284  ros::AdvertiseServiceOptions get_model_properties_aso =
285  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
286  get_model_properties_service_name,
287  boost::bind(&GazeboRosApiPlugin::getModelProperties,this,_1,_2),
289  get_model_properties_service_ = nh_->advertiseService(get_model_properties_aso);
290 
291  // Advertise more services on the custom queue
292  std::string get_model_state_service_name("get_model_state");
293  ros::AdvertiseServiceOptions get_model_state_aso =
294  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
295  get_model_state_service_name,
296  boost::bind(&GazeboRosApiPlugin::getModelState,this,_1,_2),
298  get_model_state_service_ = nh_->advertiseService(get_model_state_aso);
299 
300  // Advertise more services on the custom queue
301  std::string get_world_properties_service_name("get_world_properties");
302  ros::AdvertiseServiceOptions get_world_properties_aso =
303  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
304  get_world_properties_service_name,
305  boost::bind(&GazeboRosApiPlugin::getWorldProperties,this,_1,_2),
307  get_world_properties_service_ = nh_->advertiseService(get_world_properties_aso);
308 
309  // Advertise more services on the custom queue
310  std::string get_joint_properties_service_name("get_joint_properties");
311  ros::AdvertiseServiceOptions get_joint_properties_aso =
312  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
313  get_joint_properties_service_name,
314  boost::bind(&GazeboRosApiPlugin::getJointProperties,this,_1,_2),
316  get_joint_properties_service_ = nh_->advertiseService(get_joint_properties_aso);
317 
318  // Advertise more services on the custom queue
319  std::string get_link_properties_service_name("get_link_properties");
320  ros::AdvertiseServiceOptions get_link_properties_aso =
321  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
322  get_link_properties_service_name,
323  boost::bind(&GazeboRosApiPlugin::getLinkProperties,this,_1,_2),
325  get_link_properties_service_ = nh_->advertiseService(get_link_properties_aso);
326 
327  // Advertise more services on the custom queue
328  std::string get_link_state_service_name("get_link_state");
329  ros::AdvertiseServiceOptions get_link_state_aso =
330  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
331  get_link_state_service_name,
332  boost::bind(&GazeboRosApiPlugin::getLinkState,this,_1,_2),
334  get_link_state_service_ = nh_->advertiseService(get_link_state_aso);
335 
336  // Advertise more services on the custom queue
337  std::string get_light_properties_service_name("get_light_properties");
338  ros::AdvertiseServiceOptions get_light_properties_aso =
339  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLightProperties>(
340  get_light_properties_service_name,
341  boost::bind(&GazeboRosApiPlugin::getLightProperties,this,_1,_2),
343  get_light_properties_service_ = nh_->advertiseService(get_light_properties_aso);
344 
345  // Advertise more services on the custom queue
346  std::string set_light_properties_service_name("set_light_properties");
347  ros::AdvertiseServiceOptions set_light_properties_aso =
348  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLightProperties>(
349  set_light_properties_service_name,
350  boost::bind(&GazeboRosApiPlugin::setLightProperties,this,_1,_2),
352  set_light_properties_service_ = nh_->advertiseService(set_light_properties_aso);
353 
354  // Advertise more services on the custom queue
355  std::string get_physics_properties_service_name("get_physics_properties");
356  ros::AdvertiseServiceOptions get_physics_properties_aso =
357  ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
358  get_physics_properties_service_name,
359  boost::bind(&GazeboRosApiPlugin::getPhysicsProperties,this,_1,_2),
361  get_physics_properties_service_ = nh_->advertiseService(get_physics_properties_aso);
362 
363  // publish complete link states in world frame
364  ros::AdvertiseOptions pub_link_states_ao =
365  ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
366  "link_states",10,
367  boost::bind(&GazeboRosApiPlugin::onLinkStatesConnect,this),
370  pub_link_states_ = nh_->advertise(pub_link_states_ao);
371 
372  // publish complete model states in world frame
373  ros::AdvertiseOptions pub_model_states_ao =
374  ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
375  "model_states",10,
376  boost::bind(&GazeboRosApiPlugin::onModelStatesConnect,this),
379  pub_model_states_ = nh_->advertise(pub_model_states_ao);
380 
381  // Advertise more services on the custom queue
382  std::string set_link_properties_service_name("set_link_properties");
383  ros::AdvertiseServiceOptions set_link_properties_aso =
384  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
385  set_link_properties_service_name,
386  boost::bind(&GazeboRosApiPlugin::setLinkProperties,this,_1,_2),
388  set_link_properties_service_ = nh_->advertiseService(set_link_properties_aso);
389 
390  // Advertise more services on the custom queue
391  std::string set_physics_properties_service_name("set_physics_properties");
392  ros::AdvertiseServiceOptions set_physics_properties_aso =
393  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
394  set_physics_properties_service_name,
395  boost::bind(&GazeboRosApiPlugin::setPhysicsProperties,this,_1,_2),
397  set_physics_properties_service_ = nh_->advertiseService(set_physics_properties_aso);
398 
399  // Advertise more services on the custom queue
400  std::string set_model_state_service_name("set_model_state");
401  ros::AdvertiseServiceOptions set_model_state_aso =
402  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
403  set_model_state_service_name,
404  boost::bind(&GazeboRosApiPlugin::setModelState,this,_1,_2),
406  set_model_state_service_ = nh_->advertiseService(set_model_state_aso);
407 
408  // Advertise more services on the custom queue
409  std::string set_model_configuration_service_name("set_model_configuration");
410  ros::AdvertiseServiceOptions set_model_configuration_aso =
411  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
412  set_model_configuration_service_name,
413  boost::bind(&GazeboRosApiPlugin::setModelConfiguration,this,_1,_2),
415  set_model_configuration_service_ = nh_->advertiseService(set_model_configuration_aso);
416 
417  // Advertise more services on the custom queue
418  std::string set_joint_properties_service_name("set_joint_properties");
419  ros::AdvertiseServiceOptions set_joint_properties_aso =
420  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
421  set_joint_properties_service_name,
422  boost::bind(&GazeboRosApiPlugin::setJointProperties,this,_1,_2),
424  set_joint_properties_service_ = nh_->advertiseService(set_joint_properties_aso);
425 
426  // Advertise more services on the custom queue
427  std::string set_link_state_service_name("set_link_state");
428  ros::AdvertiseServiceOptions set_link_state_aso =
429  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
430  set_link_state_service_name,
431  boost::bind(&GazeboRosApiPlugin::setLinkState,this,_1,_2),
433  set_link_state_service_ = nh_->advertiseService(set_link_state_aso);
434 
435  // Advertise topic on custom queue
436  // topic callback version for set_link_state
437  ros::SubscribeOptions link_state_so =
438  ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
439  "set_link_state",10,
440  boost::bind( &GazeboRosApiPlugin::updateLinkState,this,_1),
442  set_link_state_topic_ = nh_->subscribe(link_state_so);
443 
444  // topic callback version for set_model_state
445  ros::SubscribeOptions model_state_so =
446  ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
447  "set_model_state",10,
448  boost::bind( &GazeboRosApiPlugin::updateModelState,this,_1),
450  set_model_state_topic_ = nh_->subscribe(model_state_so);
451 
452  // Advertise more services on the custom queue
453  std::string pause_physics_service_name("pause_physics");
454  ros::AdvertiseServiceOptions pause_physics_aso =
455  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
456  pause_physics_service_name,
457  boost::bind(&GazeboRosApiPlugin::pausePhysics,this,_1,_2),
459  pause_physics_service_ = nh_->advertiseService(pause_physics_aso);
460 
461  // Advertise more services on the custom queue
462  std::string unpause_physics_service_name("unpause_physics");
463  ros::AdvertiseServiceOptions unpause_physics_aso =
464  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
465  unpause_physics_service_name,
466  boost::bind(&GazeboRosApiPlugin::unpausePhysics,this,_1,_2),
468  unpause_physics_service_ = nh_->advertiseService(unpause_physics_aso);
469 
470  // Advertise more services on the custom queue
471  std::string apply_body_wrench_service_name("apply_body_wrench");
472  ros::AdvertiseServiceOptions apply_body_wrench_aso =
473  ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
474  apply_body_wrench_service_name,
475  boost::bind(&GazeboRosApiPlugin::applyBodyWrench,this,_1,_2),
477  apply_body_wrench_service_ = nh_->advertiseService(apply_body_wrench_aso);
478 
479  // Advertise more services on the custom queue
480  std::string apply_joint_effort_service_name("apply_joint_effort");
481  ros::AdvertiseServiceOptions apply_joint_effort_aso =
482  ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
483  apply_joint_effort_service_name,
484  boost::bind(&GazeboRosApiPlugin::applyJointEffort,this,_1,_2),
486  apply_joint_effort_service_ = nh_->advertiseService(apply_joint_effort_aso);
487 
488  // Advertise more services on the custom queue
489  std::string clear_joint_forces_service_name("clear_joint_forces");
490  ros::AdvertiseServiceOptions clear_joint_forces_aso =
491  ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
492  clear_joint_forces_service_name,
493  boost::bind(&GazeboRosApiPlugin::clearJointForces,this,_1,_2),
495  clear_joint_forces_service_ = nh_->advertiseService(clear_joint_forces_aso);
496 
497  // Advertise more services on the custom queue
498  std::string clear_body_wrenches_service_name("clear_body_wrenches");
499  ros::AdvertiseServiceOptions clear_body_wrenches_aso =
500  ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
501  clear_body_wrenches_service_name,
502  boost::bind(&GazeboRosApiPlugin::clearBodyWrenches,this,_1,_2),
504  clear_body_wrenches_service_ = nh_->advertiseService(clear_body_wrenches_aso);
505 
506  // Advertise more services on the custom queue
507  std::string reset_simulation_service_name("reset_simulation");
508  ros::AdvertiseServiceOptions reset_simulation_aso =
509  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
510  reset_simulation_service_name,
511  boost::bind(&GazeboRosApiPlugin::resetSimulation,this,_1,_2),
513  reset_simulation_service_ = nh_->advertiseService(reset_simulation_aso);
514 
515  // Advertise more services on the custom queue
516  std::string reset_world_service_name("reset_world");
517  ros::AdvertiseServiceOptions reset_world_aso =
518  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
519  reset_world_service_name,
520  boost::bind(&GazeboRosApiPlugin::resetWorld,this,_1,_2),
522  reset_world_service_ = nh_->advertiseService(reset_world_aso);
523 
524 
525  // set param for use_sim_time if not set by user already
526  if(!(nh_->hasParam("/use_sim_time")))
527  nh_->setParam("/use_sim_time", true);
528 
529  // todo: contemplate setting environment variable ROBOT=sim here???
530  nh_->getParam("pub_clock_frequency", pub_clock_frequency_);
531 #if GAZEBO_MAJOR_VERSION >= 8
532  last_pub_clock_time_ = world_->SimTime();
533 #else
534  last_pub_clock_time_ = world_->GetSimTime();
535 #endif
536 }
537 
539 {
541  if (pub_link_states_connection_count_ == 1) // connect on first subscriber
542  pub_link_states_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishLinkStates,this));
543 }
544 
546 {
548  if (pub_model_states_connection_count_ == 1) // connect on first subscriber
549  pub_model_states_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishModelStates,this));
550 }
551 
553 {
555  if (pub_link_states_connection_count_ <= 0) // disconnect with no subscribers
556  {
557  pub_link_states_event_.reset();
558  if (pub_link_states_connection_count_ < 0) // should not be possible
559  ROS_ERROR_NAMED("api_plugin", "One too mandy disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
560  }
561 }
562 
564 {
566  if (pub_model_states_connection_count_ <= 0) // disconnect with no subscribers
567  {
568  pub_model_states_event_.reset();
569  if (pub_model_states_connection_count_ < 0) // should not be possible
570  ROS_ERROR_NAMED("api_plugin", "One too mandy disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
571  }
572 }
573 
574 bool GazeboRosApiPlugin::spawnURDFModel(gazebo_msgs::SpawnModel::Request &req,
575  gazebo_msgs::SpawnModel::Response &res)
576 {
577  // get namespace for the corresponding model plugins
578  robot_namespace_ = req.robot_namespace;
579 
580  // incoming entity string
581  std::string model_xml = req.model_xml;
582 
583  if (!isURDF(model_xml))
584  {
585  ROS_ERROR_NAMED("api_plugin", "SpawnModel: Failure - entity format is invalid.");
586  res.success = false;
587  res.status_message = "SpawnModel: Failure - entity format is invalid.";
588  return false;
589  }
590 
594  {
595  std::string open_bracket("<?");
596  std::string close_bracket("?>");
597  size_t pos1 = model_xml.find(open_bracket,0);
598  size_t pos2 = model_xml.find(close_bracket,0);
599  if (pos1 != std::string::npos && pos2 != std::string::npos)
600  model_xml.replace(pos1,pos2-pos1+2,std::string(""));
601  }
602 
603  // Remove comments from URDF
604  {
605  std::string open_comment("<!--");
606  std::string close_comment("-->");
607  size_t pos1;
608  while((pos1 = model_xml.find(open_comment,0)) != std::string::npos){
609  size_t pos2 = model_xml.find(close_comment,0);
610  if (pos2 != std::string::npos)
611  model_xml.replace(pos1,pos2-pos1+3,std::string(""));
612  }
613  }
614 
615  // Now, replace package://xxx with the full path to the package
616  {
617  std::string package_prefix("package://");
618  size_t pos1 = model_xml.find(package_prefix,0);
619  while (pos1 != std::string::npos)
620  {
621  size_t pos2 = model_xml.find("/", pos1+10);
622  //ROS_DEBUG_NAMED("api_plugin", " pos %d %d",(int)pos1, (int)pos2);
623  if (pos2 == std::string::npos || pos1 >= pos2)
624  {
625  ROS_ERROR_NAMED("api_plugin", "Malformed package name?");
626  break;
627  }
628 
629  std::string package_name = model_xml.substr(pos1+10,pos2-pos1-10);
630  //ROS_DEBUG_NAMED("api_plugin", "package name [%s]", package_name.c_str());
631  std::string package_path = ros::package::getPath(package_name);
632  if (package_path.empty())
633  {
634  ROS_FATAL_NAMED("api_plugin", "Package[%s] does not have a path",package_name.c_str());
635  res.success = false;
636  res.status_message = "urdf reference package name does not exist: " + package_name;
637  return false;
638  }
639  ROS_DEBUG_ONCE_NAMED("api_plugin", "Package name [%s] has path [%s]", package_name.c_str(), package_path.c_str());
640 
641  model_xml.replace(pos1,(pos2-pos1),package_path);
642  pos1 = model_xml.find(package_prefix, pos1);
643  }
644  }
645  // ROS_DEBUG_NAMED("api_plugin", "Model XML\n\n%s\n\n ",model_xml.c_str());
646 
647  req.model_xml = model_xml;
648 
649  // Model is now considered convert to SDF
650  return spawnSDFModel(req,res);
651 }
652 
653 bool GazeboRosApiPlugin::spawnSDFModel(gazebo_msgs::SpawnModel::Request &req,
654  gazebo_msgs::SpawnModel::Response &res)
655 {
656  // incoming entity name
657  std::string model_name = req.model_name;
658 
659  // get namespace for the corresponding model plugins
660  robot_namespace_ = req.robot_namespace;
661 
662  // get initial pose of model
663  ignition::math::Vector3d initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
664  // get initial roll pitch yaw (fixed frame transform)
665  ignition::math::Quaterniond initial_q(req.initial_pose.orientation.w,req.initial_pose.orientation.x,req.initial_pose.orientation.y,req.initial_pose.orientation.z);
666 
667  // refernce frame for initial pose definition, modify initial pose if defined
668 #if GAZEBO_MAJOR_VERSION >= 8
669  gazebo::physics::EntityPtr frame = world_->EntityByName(req.reference_frame);
670 #else
671  gazebo::physics::EntityPtr frame = world_->GetEntity(req.reference_frame);
672 #endif
673  if (frame)
674  {
675  // convert to relative pose
676 #if GAZEBO_MAJOR_VERSION >= 8
677  ignition::math::Pose3d frame_pose = frame->WorldPose();
678 #else
679  ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
680 #endif
681  initial_xyz = frame_pose.Pos() + frame_pose.Rot().RotateVector(initial_xyz);
682  initial_q = frame_pose.Rot() * initial_q;
683  }
684 
686  else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
687  {
688  ROS_DEBUG_NAMED("api_plugin", "SpawnModel: reference_frame is empty/world/map, using inertial frame");
689  }
690  else
691  {
692  res.success = false;
693  res.status_message = "SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
694  return true;
695  }
696 
697  // incoming robot model string
698  std::string model_xml = req.model_xml;
699 
700  // store resulting Gazebo Model XML to be sent to spawn queue
701  // get incoming string containg either an URDF or a Gazebo Model XML
702  // grab from parameter server if necessary convert to SDF if necessary
703  stripXmlDeclaration(model_xml);
704 
705  // put string in TiXmlDocument for manipulation
706  TiXmlDocument gazebo_model_xml;
707  gazebo_model_xml.Parse(model_xml.c_str());
708 
709  // optional model manipulations: update initial pose && replace model name
710  if (isSDF(model_xml))
711  {
712  updateSDFAttributes(gazebo_model_xml, model_name, initial_xyz, initial_q);
713 
714  // Walk recursively through the entire SDF, locate plugin tags and
715  // add robotNamespace as a child with the correct namespace
716  if (!this->robot_namespace_.empty())
717  {
718  // Get root element for SDF
719  // TODO: implement the spawning also with <light></light> and <model></model>
720  TiXmlNode* model_tixml = gazebo_model_xml.FirstChild("sdf");
721  model_tixml = (!model_tixml) ?
722  gazebo_model_xml.FirstChild("gazebo") : model_tixml;
723  if (model_tixml)
724  {
725  walkChildAddRobotNamespace(model_tixml);
726  }
727  else
728  {
729  ROS_WARN_NAMED("api_plugin", "Unable to add robot namespace to xml");
730  }
731  }
732  }
733  else if (isURDF(model_xml))
734  {
735  updateURDFModelPose(gazebo_model_xml, initial_xyz, initial_q);
736  updateURDFName(gazebo_model_xml, model_name);
737 
738  // Walk recursively through the entire URDF, locate plugin tags and
739  // add robotNamespace as a child with the correct namespace
740  if (!this->robot_namespace_.empty())
741  {
742  // Get root element for URDF
743  TiXmlNode* model_tixml = gazebo_model_xml.FirstChild("robot");
744  if (model_tixml)
745  {
746  walkChildAddRobotNamespace(model_tixml);
747  }
748  else
749  {
750  ROS_WARN_NAMED("api_plugin", "Unable to add robot namespace to xml");
751  }
752  }
753  }
754  else
755  {
756  ROS_ERROR_NAMED("api_plugin", "GazeboRosApiPlugin SpawnModel Failure: input xml format not recognized");
757  res.success = false;
758  res.status_message = "GazeboRosApiPlugin SpawnModel Failure: input model_xml not SDF or URDF, or cannot be converted to Gazebo compatible format.";
759  return true;
760  }
761 
762  // do spawning check if spawn worked, return response
763  return spawnAndConform(gazebo_model_xml, model_name, res);
764 }
765 
766 bool GazeboRosApiPlugin::deleteModel(gazebo_msgs::DeleteModel::Request &req,
767  gazebo_msgs::DeleteModel::Response &res)
768 {
769  // clear forces, etc for the body in question
770 #if GAZEBO_MAJOR_VERSION >= 8
771  gazebo::physics::ModelPtr model = world_->ModelByName(req.model_name);
772 #else
773  gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
774 #endif
775  if (!model)
776  {
777  ROS_ERROR_NAMED("api_plugin", "DeleteModel: model [%s] does not exist",req.model_name.c_str());
778  res.success = false;
779  res.status_message = "DeleteModel: model does not exist";
780  return true;
781  }
782 
783  // delete wrench jobs on bodies
784  for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
785  {
786  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
787  if (body)
788  {
789  // look for it in jobs, delete body wrench jobs
790  clearBodyWrenches(body->GetScopedName());
791  }
792  }
793 
794  // delete force jobs on joints
795  gazebo::physics::Joint_V joints = model->GetJoints();
796  for (unsigned int i=0;i< joints.size(); i++)
797  {
798  // look for it in jobs, delete joint force jobs
799  clearJointForces(joints[i]->GetName());
800  }
801 
802  // send delete model request
803  gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest("entity_delete",req.model_name);
804  request_pub_->Publish(*msg,true);
805 
806  ros::Duration model_spawn_timeout(60.0);
807  ros::Time timeout = ros::Time::now() + model_spawn_timeout;
808  // wait and verify that model is deleted
809  while (true)
810  {
811  if (ros::Time::now() > timeout)
812  {
813  res.success = false;
814  res.status_message = "DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation";
815  return true;
816  }
817  {
818  //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
819 #if GAZEBO_MAJOR_VERSION >= 8
820  if (!world_->ModelByName(req.model_name)) break;
821 #else
822  if (!world_->GetModel(req.model_name)) break;
823 #endif
824  }
825  ROS_DEBUG_NAMED("api_plugin", "Waiting for model deletion (%s)",req.model_name.c_str());
826  usleep(1000);
827  }
828 
829  // set result
830  res.success = true;
831  res.status_message = "DeleteModel: successfully deleted model";
832  return true;
833 }
834 
835 bool GazeboRosApiPlugin::deleteLight(gazebo_msgs::DeleteLight::Request &req,
836  gazebo_msgs::DeleteLight::Response &res)
837 {
838 #if GAZEBO_MAJOR_VERSION >= 8
839  gazebo::physics::LightPtr phy_light = world_->LightByName(req.light_name);
840 #else
841  gazebo::physics::LightPtr phy_light = world_->Light(req.light_name);
842 #endif
843 
844  if (phy_light == NULL)
845  {
846  res.success = false;
847  res.status_message = "DeleteLight: Requested light " + req.light_name + " not found!";
848  }
849  else
850  {
851  gazebo::msgs::Request* msg = gazebo::msgs::CreateRequest("entity_delete", req.light_name);
852  request_pub_->Publish(*msg, true);
853 
854  res.success = false;
855 
856  for (int i = 0; i < 100; i++)
857  {
858 #if GAZEBO_MAJOR_VERSION >= 8
859  phy_light = world_->LightByName(req.light_name);
860 #else
861  phy_light = world_->Light(req.light_name);
862 #endif
863  if (phy_light == NULL)
864  {
865  res.success = true;
866  res.status_message = "DeleteLight: " + req.light_name + " successfully deleted";
867  return true;
868  }
869  // Check every 100ms
870  usleep(100000);
871  }
872  }
873 
874  res.status_message = "DeleteLight: Timeout reached while removing light \"" + req.light_name
875  + "\"";
876 
877  return true;
878 }
879 
880 bool GazeboRosApiPlugin::getModelState(gazebo_msgs::GetModelState::Request &req,
881  gazebo_msgs::GetModelState::Response &res)
882 {
883 #if GAZEBO_MAJOR_VERSION >= 8
884  gazebo::physics::ModelPtr model = world_->ModelByName(req.model_name);
885  gazebo::physics::EntityPtr frame = world_->EntityByName(req.relative_entity_name);
886 #else
887  gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
888  gazebo::physics::EntityPtr frame = world_->GetEntity(req.relative_entity_name);
889 #endif
890  if (!model)
891  {
892  ROS_ERROR_NAMED("api_plugin", "GetModelState: model [%s] does not exist",req.model_name.c_str());
893  res.success = false;
894  res.status_message = "GetModelState: model does not exist";
895  return true;
896  }
897  else
898  {
904  {
905  std::map<std::string, unsigned int>::iterator it = access_count_get_model_state_.find(req.model_name);
906  if(it == access_count_get_model_state_.end())
907  {
908  access_count_get_model_state_.insert( std::pair<std::string, unsigned int>(req.model_name, 1) );
909  res.header.seq = 1;
910  }
911  else
912  {
913  it->second++;
914  res.header.seq = it->second;
915  }
916  res.header.stamp = ros::Time::now();
917  res.header.frame_id = req.relative_entity_name;
918  }
919  // get model pose
920  // get model twist
921 #if GAZEBO_MAJOR_VERSION >= 8
922  ignition::math::Pose3d model_pose = model->WorldPose();
923  ignition::math::Vector3d model_linear_vel = model->WorldLinearVel();
924  ignition::math::Vector3d model_angular_vel = model->WorldAngularVel();
925 #else
926  ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
927  ignition::math::Vector3d model_linear_vel = model->GetWorldLinearVel().Ign();
928  ignition::math::Vector3d model_angular_vel = model->GetWorldAngularVel().Ign();
929 #endif
930  ignition::math::Vector3d model_pos = model_pose.Pos();
931  ignition::math::Quaterniond model_rot = model_pose.Rot();
932 
933 
934 
935  if (frame)
936  {
937  // convert to relative pose, rates
938 #if GAZEBO_MAJOR_VERSION >= 8
939  ignition::math::Pose3d frame_pose = frame->WorldPose();
940  ignition::math::Vector3d frame_vpos = frame->WorldLinearVel(); // get velocity in gazebo frame
941  ignition::math::Vector3d frame_veul = frame->WorldAngularVel(); // get velocity in gazebo frame
942 #else
943  ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
944  ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign(); // get velocity in gazebo frame
945  ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign(); // get velocity in gazebo frame
946 #endif
947  ignition::math::Pose3d model_rel_pose = model_pose - frame_pose;
948  model_pos = model_rel_pose.Pos();
949  model_rot = model_rel_pose.Rot();
950 
951  model_linear_vel = frame_pose.Rot().RotateVectorReverse(model_linear_vel - frame_vpos);
952  model_angular_vel = frame_pose.Rot().RotateVectorReverse(model_angular_vel - frame_veul);
953  }
955  else if (req.relative_entity_name == "" || req.relative_entity_name == "world" || req.relative_entity_name == "map" || req.relative_entity_name == "/map")
956  {
957  ROS_DEBUG_NAMED("api_plugin", "GetModelState: relative_entity_name is empty/world/map, using inertial frame");
958  }
959  else
960  {
961  res.success = false;
962  res.status_message = "GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
963  return true;
964  }
965 
966  // fill in response
967  res.pose.position.x = model_pos.X();
968  res.pose.position.y = model_pos.Y();
969  res.pose.position.z = model_pos.Z();
970  res.pose.orientation.w = model_rot.W();
971  res.pose.orientation.x = model_rot.X();
972  res.pose.orientation.y = model_rot.Y();
973  res.pose.orientation.z = model_rot.Z();
974 
975  res.twist.linear.x = model_linear_vel.X();
976  res.twist.linear.y = model_linear_vel.Y();
977  res.twist.linear.z = model_linear_vel.Z();
978  res.twist.angular.x = model_angular_vel.X();
979  res.twist.angular.y = model_angular_vel.Y();
980  res.twist.angular.z = model_angular_vel.Z();
981 
982  res.success = true;
983  res.status_message = "GetModelState: got properties";
984  return true;
985  }
986  return true;
987 }
988 
989 bool GazeboRosApiPlugin::getModelProperties(gazebo_msgs::GetModelProperties::Request &req,
990  gazebo_msgs::GetModelProperties::Response &res)
991 {
992 #if GAZEBO_MAJOR_VERSION >= 8
993  gazebo::physics::ModelPtr model = world_->ModelByName(req.model_name);
994 #else
995  gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
996 #endif
997  if (!model)
998  {
999  ROS_ERROR_NAMED("api_plugin", "GetModelProperties: model [%s] does not exist",req.model_name.c_str());
1000  res.success = false;
1001  res.status_message = "GetModelProperties: model does not exist";
1002  return true;
1003  }
1004  else
1005  {
1006  // get model parent name
1007  gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
1008  if (parent_model) res.parent_model_name = parent_model->GetName();
1009 
1010  // get list of child bodies, geoms
1011  res.body_names.clear();
1012  res.geom_names.clear();
1013  for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
1014  {
1015  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
1016  if (body)
1017  {
1018  res.body_names.push_back(body->GetName());
1019  // get list of geoms
1020  for (unsigned int j = 0; j < body->GetChildCount() ; j++)
1021  {
1022  gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
1023  if (geom)
1024  res.geom_names.push_back(geom->GetName());
1025  }
1026  }
1027  }
1028 
1029  // get list of joints
1030  res.joint_names.clear();
1031 
1032  gazebo::physics::Joint_V joints = model->GetJoints();
1033  for (unsigned int i=0;i< joints.size(); i++)
1034  res.joint_names.push_back( joints[i]->GetName() );
1035 
1036  // get children model names
1037  res.child_model_names.clear();
1038  for (unsigned int j = 0; j < model->GetChildCount(); j++)
1039  {
1040  gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
1041  if (child_model)
1042  res.child_model_names.push_back(child_model->GetName() );
1043  }
1044 
1045  // is model static
1046  res.is_static = model->IsStatic();
1047 
1048  res.success = true;
1049  res.status_message = "GetModelProperties: got properties";
1050  return true;
1051  }
1052  return true;
1053 }
1054 
1055 bool GazeboRosApiPlugin::getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,
1056  gazebo_msgs::GetWorldProperties::Response &res)
1057 {
1058  res.model_names.clear();
1059 #if GAZEBO_MAJOR_VERSION >= 8
1060  res.sim_time = world_->SimTime().Double();
1061  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
1062  res.model_names.push_back(world_->ModelByIndex(i)->GetName());
1063 #else
1064  res.sim_time = world_->GetSimTime().Double();
1065  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
1066  res.model_names.push_back(world_->GetModel(i)->GetName());
1067 #endif
1068  gzerr << "disablign rendering has not been implemented, rendering is always enabled\n";
1069  res.rendering_enabled = true; //world->GetRenderEngineEnabled();
1070  res.success = true;
1071  res.status_message = "GetWorldProperties: got properties";
1072  return true;
1073 }
1074 
1075 bool GazeboRosApiPlugin::getJointProperties(gazebo_msgs::GetJointProperties::Request &req,
1076  gazebo_msgs::GetJointProperties::Response &res)
1077 {
1078  gazebo::physics::JointPtr joint;
1079 #if GAZEBO_MAJOR_VERSION >= 8
1080  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
1081  {
1082  joint = world_->ModelByIndex(i)->GetJoint(req.joint_name);
1083 #else
1084  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
1085  {
1086  joint = world_->GetModel(i)->GetJoint(req.joint_name);
1087 #endif
1088  if (joint) break;
1089  }
1090 
1091  if (!joint)
1092  {
1093  res.success = false;
1094  res.status_message = "GetJointProperties: joint not found";
1095  return true;
1096  }
1097  else
1098  {
1100  res.type = res.REVOLUTE;
1101 
1102  res.damping.clear(); // to be added to gazebo
1103  //res.damping.push_back(joint->GetDamping(0));
1104 
1105  res.position.clear();
1106 #if GAZEBO_MAJOR_VERSION >= 8
1107  res.position.push_back(joint->Position(0));
1108 #else
1109  res.position.push_back(joint->GetAngle(0).Radian());
1110 #endif
1111 
1112  res.rate.clear(); // use GetVelocity(i)
1113  res.rate.push_back(joint->GetVelocity(0));
1114 
1115  res.success = true;
1116  res.status_message = "GetJointProperties: got properties";
1117  return true;
1118  }
1119 }
1120 
1121 bool GazeboRosApiPlugin::getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,
1122  gazebo_msgs::GetLinkProperties::Response &res)
1123 {
1124 #if GAZEBO_MAJOR_VERSION >= 8
1125  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->EntityByName(req.link_name));
1126 #else
1127  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
1128 #endif
1129  if (!body)
1130  {
1131  res.success = false;
1132  res.status_message = "GetLinkProperties: link not found, did you forget to scope the link by model name?";
1133  return true;
1134  }
1135  else
1136  {
1138  res.gravity_mode = body->GetGravityMode();
1139 
1140  gazebo::physics::InertialPtr inertia = body->GetInertial();
1141 
1142 #if GAZEBO_MAJOR_VERSION >= 8
1143  res.mass = body->GetInertial()->Mass();
1144 
1145  res.ixx = inertia->IXX();
1146  res.iyy = inertia->IYY();
1147  res.izz = inertia->IZZ();
1148  res.ixy = inertia->IXY();
1149  res.ixz = inertia->IXZ();
1150  res.iyz = inertia->IYZ();
1151 
1152  ignition::math::Vector3d com = body->GetInertial()->CoG();
1153 #else
1154  res.mass = body->GetInertial()->GetMass();
1155 
1156  res.ixx = inertia->GetIXX();
1157  res.iyy = inertia->GetIYY();
1158  res.izz = inertia->GetIZZ();
1159  res.ixy = inertia->GetIXY();
1160  res.ixz = inertia->GetIXZ();
1161  res.iyz = inertia->GetIYZ();
1162 
1163  ignition::math::Vector3d com = body->GetInertial()->GetCoG().Ign();
1164 #endif
1165  res.com.position.x = com.X();
1166  res.com.position.y = com.Y();
1167  res.com.position.z = com.Z();
1168  res.com.orientation.x = 0; // @todo: gazebo do not support rotated inertia yet
1169  res.com.orientation.y = 0;
1170  res.com.orientation.z = 0;
1171  res.com.orientation.w = 1;
1172 
1173  res.success = true;
1174  res.status_message = "GetLinkProperties: got properties";
1175  return true;
1176  }
1177 }
1178 
1179 bool GazeboRosApiPlugin::getLinkState(gazebo_msgs::GetLinkState::Request &req,
1180  gazebo_msgs::GetLinkState::Response &res)
1181 {
1182 #if GAZEBO_MAJOR_VERSION >= 8
1183  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->EntityByName(req.link_name));
1184  gazebo::physics::EntityPtr frame = world_->EntityByName(req.reference_frame);
1185 #else
1186  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
1187  gazebo::physics::EntityPtr frame = world_->GetEntity(req.reference_frame);
1188 #endif
1189 
1190  if (!body)
1191  {
1192  res.success = false;
1193  res.status_message = "GetLinkState: link not found, did you forget to scope the link by model name?";
1194  return true;
1195  }
1196 
1197  // get body pose
1198  // Get inertial rates
1199 #if GAZEBO_MAJOR_VERSION >= 8
1200  ignition::math::Pose3d body_pose = body->WorldPose();
1201  ignition::math::Vector3d body_vpos = body->WorldLinearVel(); // get velocity in gazebo frame
1202  ignition::math::Vector3d body_veul = body->WorldAngularVel(); // get velocity in gazebo frame
1203 #else
1204  ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
1205  ignition::math::Vector3d body_vpos = body->GetWorldLinearVel().Ign(); // get velocity in gazebo frame
1206  ignition::math::Vector3d body_veul = body->GetWorldAngularVel().Ign(); // get velocity in gazebo frame
1207 #endif
1208 
1209  if (frame)
1210  {
1211  // convert to relative pose, rates
1212 #if GAZEBO_MAJOR_VERSION >= 8
1213  ignition::math::Pose3d frame_pose = frame->WorldPose();
1214  ignition::math::Vector3d frame_vpos = frame->WorldLinearVel(); // get velocity in gazebo frame
1215  ignition::math::Vector3d frame_veul = frame->WorldAngularVel(); // get velocity in gazebo frame
1216 #else
1217  ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1218  ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign(); // get velocity in gazebo frame
1219  ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign(); // get velocity in gazebo frame
1220 #endif
1221  body_pose = body_pose - frame_pose;
1222 
1223  body_vpos = frame_pose.Rot().RotateVectorReverse(body_vpos - frame_vpos);
1224  body_veul = frame_pose.Rot().RotateVectorReverse(body_veul - frame_veul);
1225  }
1227  else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
1228  {
1229  ROS_DEBUG_NAMED("api_plugin", "GetLinkState: reference_frame is empty/world/map, using inertial frame");
1230  }
1231  else
1232  {
1233  res.success = false;
1234  res.status_message = "GetLinkState: reference reference_frame not found, did you forget to scope the link by model name?";
1235  return true;
1236  }
1237 
1238  res.link_state.link_name = req.link_name;
1239  res.link_state.pose.position.x = body_pose.Pos().X();
1240  res.link_state.pose.position.y = body_pose.Pos().Y();
1241  res.link_state.pose.position.z = body_pose.Pos().Z();
1242  res.link_state.pose.orientation.x = body_pose.Rot().X();
1243  res.link_state.pose.orientation.y = body_pose.Rot().Y();
1244  res.link_state.pose.orientation.z = body_pose.Rot().Z();
1245  res.link_state.pose.orientation.w = body_pose.Rot().W();
1246  res.link_state.twist.linear.x = body_vpos.X();
1247  res.link_state.twist.linear.y = body_vpos.Y();
1248  res.link_state.twist.linear.z = body_vpos.Z();
1249  res.link_state.twist.angular.x = body_veul.X();
1250  res.link_state.twist.angular.y = body_veul.Y();
1251  res.link_state.twist.angular.z = body_veul.Z();
1252  res.link_state.reference_frame = req.reference_frame;
1253 
1254  res.success = true;
1255  res.status_message = "GetLinkState: got state";
1256  return true;
1257 }
1258 
1259 bool GazeboRosApiPlugin::getLightProperties(gazebo_msgs::GetLightProperties::Request &req,
1260  gazebo_msgs::GetLightProperties::Response &res)
1261 {
1262 #if GAZEBO_MAJOR_VERSION >= 8
1263  gazebo::physics::LightPtr phy_light = world_->LightByName(req.light_name);
1264 #else
1265  gazebo::physics::LightPtr phy_light = world_->Light(req.light_name);
1266 #endif
1267 
1268  if (phy_light == NULL)
1269  {
1270  res.success = false;
1271  res.status_message = "getLightProperties: Requested light " + req.light_name + " not found!";
1272  }
1273  else
1274  {
1275  gazebo::msgs::Light light;
1276  phy_light->FillMsg(light);
1277 
1278  res.diffuse.r = light.diffuse().r();
1279  res.diffuse.g = light.diffuse().g();
1280  res.diffuse.b = light.diffuse().b();
1281  res.diffuse.a = light.diffuse().a();
1282 
1283  res.attenuation_constant = light.attenuation_constant();
1284  res.attenuation_linear = light.attenuation_linear();
1285  res.attenuation_quadratic = light.attenuation_quadratic();
1286 
1287  res.success = true;
1288  }
1289 
1290  return true;
1291 }
1292 
1293 bool GazeboRosApiPlugin::setLightProperties(gazebo_msgs::SetLightProperties::Request &req,
1294  gazebo_msgs::SetLightProperties::Response &res)
1295 {
1296 #if GAZEBO_MAJOR_VERSION >= 8
1297  gazebo::physics::LightPtr phy_light = world_->LightByName(req.light_name);
1298 #else
1299  gazebo::physics::LightPtr phy_light = world_->Light(req.light_name);
1300 #endif
1301 
1302  if (phy_light == NULL)
1303  {
1304  res.success = false;
1305  res.status_message = "setLightProperties: Requested light " + req.light_name + " not found!";
1306  }
1307  else
1308  {
1309  gazebo::msgs::Light light;
1310 
1311  phy_light->FillMsg(light);
1312 
1313  light.mutable_diffuse()->set_r(req.diffuse.r);
1314  light.mutable_diffuse()->set_g(req.diffuse.g);
1315  light.mutable_diffuse()->set_b(req.diffuse.b);
1316  light.mutable_diffuse()->set_a(req.diffuse.a);
1317 
1318  light.set_attenuation_constant(req.attenuation_constant);
1319  light.set_attenuation_linear(req.attenuation_linear);
1320  light.set_attenuation_quadratic(req.attenuation_quadratic);
1321 
1322  light_modify_pub_->Publish(light, true);
1323 
1324  res.success = true;
1325  }
1326 
1327  return true;
1328 }
1329 
1330 bool GazeboRosApiPlugin::setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req,
1331  gazebo_msgs::SetLinkProperties::Response &res)
1332 {
1333 #if GAZEBO_MAJOR_VERSION >= 8
1334  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->EntityByName(req.link_name));
1335 #else
1336  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
1337 #endif
1338  if (!body)
1339  {
1340  res.success = false;
1341  res.status_message = "SetLinkProperties: link not found, did you forget to scope the link by model name?";
1342  return true;
1343  }
1344  else
1345  {
1346  gazebo::physics::InertialPtr mass = body->GetInertial();
1347  // @todo: FIXME: add inertia matrix rotation to Gazebo
1348  // mass.SetInertiaRotation(ignition::math::Quaterniondion(req.com.orientation.w,res.com.orientation.x,req.com.orientation.y req.com.orientation.z));
1349  mass->SetCoG(ignition::math::Vector3d(req.com.position.x,req.com.position.y,req.com.position.z));
1350  mass->SetInertiaMatrix(req.ixx,req.iyy,req.izz,req.ixy,req.ixz,req.iyz);
1351  mass->SetMass(req.mass);
1352  body->SetGravityMode(req.gravity_mode);
1353  // @todo: mass change unverified
1354  res.success = true;
1355  res.status_message = "SetLinkProperties: properties set";
1356  return true;
1357  }
1358 }
1359 
1360 bool GazeboRosApiPlugin::setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req,
1361  gazebo_msgs::SetPhysicsProperties::Response &res)
1362 {
1363  // pause simulation if requested
1364  bool is_paused = world_->IsPaused();
1365  world_->SetPaused(true);
1366  world_->SetGravity(ignition::math::Vector3d(req.gravity.x,req.gravity.y,req.gravity.z));
1367 
1368  // supported updates
1369 #if GAZEBO_MAJOR_VERSION >= 8
1370  gazebo::physics::PhysicsEnginePtr pe = (world_->Physics());
1371 #else
1372  gazebo::physics::PhysicsEnginePtr pe = (world_->GetPhysicsEngine());
1373 #endif
1374  pe->SetMaxStepSize(req.time_step);
1375  pe->SetRealTimeUpdateRate(req.max_update_rate);
1376 
1377  if (pe->GetType() == "ode")
1378  {
1379  // stuff only works in ODE right now
1380  pe->SetAutoDisableFlag(req.ode_config.auto_disable_bodies);
1381  pe->SetParam("precon_iters", int(req.ode_config.sor_pgs_precon_iters));
1382  pe->SetParam("iters", int(req.ode_config.sor_pgs_iters));
1383  pe->SetParam("sor", req.ode_config.sor_pgs_w);
1384  pe->SetParam("cfm", req.ode_config.cfm);
1385  pe->SetParam("erp", req.ode_config.erp);
1386  pe->SetParam("contact_surface_layer",
1387  req.ode_config.contact_surface_layer);
1388  pe->SetParam("contact_max_correcting_vel",
1389  req.ode_config.contact_max_correcting_vel);
1390  pe->SetParam("max_contacts", int(req.ode_config.max_contacts));
1391 
1392  world_->SetPaused(is_paused);
1393 
1394  res.success = true;
1395  res.status_message = "physics engine updated";
1396  }
1397  else
1398  {
1400  ROS_ERROR_NAMED("api_plugin", "ROS set_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1401  res.success = false;
1402  res.status_message = "Physics engine [" + pe->GetType() + "]: set_physics_properties not supported.";
1403  }
1404  return res.success;
1405 }
1406 
1407 bool GazeboRosApiPlugin::getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req,
1408  gazebo_msgs::GetPhysicsProperties::Response &res)
1409 {
1410  // supported updates
1411 #if GAZEBO_MAJOR_VERSION >= 8
1412  gazebo::physics::PhysicsEnginePtr pe = (world_->Physics());
1413 #else
1414  gazebo::physics::PhysicsEnginePtr pe = (world_->GetPhysicsEngine());
1415 #endif
1416  res.time_step = pe->GetMaxStepSize();
1417  res.pause = world_->IsPaused();
1418  res.max_update_rate = pe->GetRealTimeUpdateRate();
1419  ignition::math::Vector3d gravity = world_->Gravity();
1420  res.gravity.x = gravity.X();
1421  res.gravity.y = gravity.Y();
1422  res.gravity.z = gravity.Z();
1423 
1424  // stuff only works in ODE right now
1425  if (pe->GetType() == "ode")
1426  {
1427  res.ode_config.auto_disable_bodies =
1428  pe->GetAutoDisableFlag();
1429  res.ode_config.sor_pgs_precon_iters = boost::any_cast<int>(
1430  pe->GetParam("precon_iters"));
1431  res.ode_config.sor_pgs_iters = boost::any_cast<int>(
1432  pe->GetParam("iters"));
1433  res.ode_config.sor_pgs_w = boost::any_cast<double>(
1434  pe->GetParam("sor"));
1435  res.ode_config.contact_surface_layer = boost::any_cast<double>(
1436  pe->GetParam("contact_surface_layer"));
1437  res.ode_config.contact_max_correcting_vel = boost::any_cast<double>(
1438  pe->GetParam("contact_max_correcting_vel"));
1439  res.ode_config.cfm = boost::any_cast<double>(
1440  pe->GetParam("cfm"));
1441  res.ode_config.erp = boost::any_cast<double>(
1442  pe->GetParam("erp"));
1443  res.ode_config.max_contacts = boost::any_cast<int>(
1444  pe->GetParam("max_contacts"));
1445 
1446  res.success = true;
1447  res.status_message = "GetPhysicsProperties: got properties";
1448  }
1449  else
1450  {
1452  ROS_ERROR_NAMED("api_plugin", "ROS get_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1453  res.success = false;
1454  res.status_message = "Physics engine [" + pe->GetType() + "]: get_physics_properties not supported.";
1455  }
1456  return res.success;
1457 }
1458 
1459 bool GazeboRosApiPlugin::setJointProperties(gazebo_msgs::SetJointProperties::Request &req,
1460  gazebo_msgs::SetJointProperties::Response &res)
1461 {
1463  gazebo::physics::JointPtr joint;
1464 #if GAZEBO_MAJOR_VERSION >= 8
1465  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
1466  {
1467  joint = world_->ModelByIndex(i)->GetJoint(req.joint_name);
1468 #else
1469  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
1470  {
1471  joint = world_->GetModel(i)->GetJoint(req.joint_name);
1472 #endif
1473  if (joint) break;
1474  }
1475 
1476  if (!joint)
1477  {
1478  res.success = false;
1479  res.status_message = "SetJointProperties: joint not found";
1480  return true;
1481  }
1482  else
1483  {
1484  for(unsigned int i=0;i< req.ode_joint_config.damping.size();i++)
1485  joint->SetDamping(i,req.ode_joint_config.damping[i]);
1486  for(unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
1487  joint->SetParam("hi_stop",i,req.ode_joint_config.hiStop[i]);
1488  for(unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
1489  joint->SetParam("lo_stop",i,req.ode_joint_config.loStop[i]);
1490  for(unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
1491  joint->SetParam("erp",i,req.ode_joint_config.erp[i]);
1492  for(unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
1493  joint->SetParam("cfm",i,req.ode_joint_config.cfm[i]);
1494  for(unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
1495  joint->SetParam("stop_erp",i,req.ode_joint_config.stop_erp[i]);
1496  for(unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
1497  joint->SetParam("stop_cfm",i,req.ode_joint_config.stop_cfm[i]);
1498  for(unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
1499  joint->SetParam("fudge_factor",i,req.ode_joint_config.fudge_factor[i]);
1500  for(unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
1501  joint->SetParam("fmax",i,req.ode_joint_config.fmax[i]);
1502  for(unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
1503  joint->SetParam("vel",i,req.ode_joint_config.vel[i]);
1504 
1505  res.success = true;
1506  res.status_message = "SetJointProperties: properties set";
1507  return true;
1508  }
1509 }
1510 
1511 bool GazeboRosApiPlugin::setModelState(gazebo_msgs::SetModelState::Request &req,
1512  gazebo_msgs::SetModelState::Response &res)
1513 {
1514  ignition::math::Vector3d target_pos(req.model_state.pose.position.x,req.model_state.pose.position.y,req.model_state.pose.position.z);
1515  ignition::math::Quaterniond 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);
1516  target_rot.Normalize(); // eliminates invalid rotation (0, 0, 0, 0)
1517  ignition::math::Pose3d target_pose(target_pos,target_rot);
1518  ignition::math::Vector3d target_pos_dot(req.model_state.twist.linear.x,req.model_state.twist.linear.y,req.model_state.twist.linear.z);
1519  ignition::math::Vector3d target_rot_dot(req.model_state.twist.angular.x,req.model_state.twist.angular.y,req.model_state.twist.angular.z);
1520 
1521 #if GAZEBO_MAJOR_VERSION >= 8
1522  gazebo::physics::ModelPtr model = world_->ModelByName(req.model_state.model_name);
1523 #else
1524  gazebo::physics::ModelPtr model = world_->GetModel(req.model_state.model_name);
1525 #endif
1526  if (!model)
1527  {
1528  ROS_ERROR_NAMED("api_plugin", "Updating ModelState: model [%s] does not exist",req.model_state.model_name.c_str());
1529  res.success = false;
1530  res.status_message = "SetModelState: model does not exist";
1531  return true;
1532  }
1533  else
1534  {
1535 #if GAZEBO_MAJOR_VERSION >= 8
1536  gazebo::physics::EntityPtr relative_entity = world_->EntityByName(req.model_state.reference_frame);
1537 #else
1538  gazebo::physics::EntityPtr relative_entity = world_->GetEntity(req.model_state.reference_frame);
1539 #endif
1540  if (relative_entity)
1541  {
1542 #if GAZEBO_MAJOR_VERSION >= 8
1543  ignition::math::Pose3d frame_pose = relative_entity->WorldPose(); // - myBody->GetCoMPose();
1544 #else
1545  ignition::math::Pose3d frame_pose = relative_entity->GetWorldPose().Ign(); // - myBody->GetCoMPose();
1546 #endif
1547 
1548  target_pose = target_pose + frame_pose;
1549 
1550  // Velocities should be commanded in the requested reference
1551  // frame, so we need to translate them to the world frame
1552  target_pos_dot = frame_pose.Rot().RotateVector(target_pos_dot);
1553  target_rot_dot = frame_pose.Rot().RotateVector(target_rot_dot);
1554  }
1556  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" )
1557  {
1558  ROS_DEBUG_NAMED("api_plugin", "Updating ModelState: reference frame is empty/world/map, usig inertial frame");
1559  }
1560  else
1561  {
1562  ROS_ERROR_NAMED("api_plugin", "Updating ModelState: for model[%s], specified reference frame entity [%s] does not exist",
1563  req.model_state.model_name.c_str(),req.model_state.reference_frame.c_str());
1564  res.success = false;
1565  res.status_message = "SetModelState: specified reference frame entity does not exist";
1566  return true;
1567  }
1568 
1569  //ROS_ERROR_NAMED("api_plugin", "target state: %f %f %f",target_pose.Pos().X(),target_pose.Pos().Y(),target_pose.Pos().Z());
1570  bool is_paused = world_->IsPaused();
1571  world_->SetPaused(true);
1572  model->SetWorldPose(target_pose);
1573  world_->SetPaused(is_paused);
1574 #if GAZEBO_MAJOR_VERSION >= 8
1575  //ignition::math::Pose3d p3d = model->WorldPose();
1576 #else
1577  //ignition::math::Pose3d p3d = model->GetWorldPose().Ign();
1578 #endif
1579  //ROS_ERROR_NAMED("api_plugin", "model updated state: %f %f %f",p3d.Pos().X(),p3d.Pos().Y(),p3d.Pos().Z());
1580 
1581  // set model velocity
1582  model->SetLinearVel(target_pos_dot);
1583  model->SetAngularVel(target_rot_dot);
1584 
1585  res.success = true;
1586  res.status_message = "SetModelState: set model state done";
1587  return true;
1588  }
1589 }
1590 
1591 void GazeboRosApiPlugin::updateModelState(const gazebo_msgs::ModelState::ConstPtr& model_state)
1592 {
1593  gazebo_msgs::SetModelState::Response res;
1594  gazebo_msgs::SetModelState::Request req;
1595  req.model_state = *model_state;
1596  /*bool success =*/ setModelState(req,res);
1597 }
1598 
1599 bool GazeboRosApiPlugin::applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req,
1600  gazebo_msgs::ApplyJointEffort::Response &res)
1601 {
1602  gazebo::physics::JointPtr joint;
1603 #if GAZEBO_MAJOR_VERSION >= 8
1604  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
1605  {
1606  joint = world_->ModelByIndex(i)->GetJoint(req.joint_name);
1607 #else
1608  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
1609  {
1610  joint = world_->GetModel(i)->GetJoint(req.joint_name);
1611 #endif
1612  if (joint)
1613  {
1615  fjj->joint = joint;
1616  fjj->force = req.effort;
1617  fjj->start_time = req.start_time;
1618 #if GAZEBO_MAJOR_VERSION >= 8
1619  if (fjj->start_time < ros::Time(world_->SimTime().Double()))
1620  fjj->start_time = ros::Time(world_->SimTime().Double());
1621 #else
1622  if (fjj->start_time < ros::Time(world_->GetSimTime().Double()))
1623  fjj->start_time = ros::Time(world_->GetSimTime().Double());
1624 #endif
1625  fjj->duration = req.duration;
1626  lock_.lock();
1627  force_joint_jobs_.push_back(fjj);
1628  lock_.unlock();
1629 
1630  res.success = true;
1631  res.status_message = "ApplyJointEffort: effort set";
1632  return true;
1633  }
1634  }
1635 
1636  res.success = false;
1637  res.status_message = "ApplyJointEffort: joint not found";
1638  return true;
1639 }
1640 
1641 bool GazeboRosApiPlugin::resetSimulation(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
1642 {
1643  world_->Reset();
1644  return true;
1645 }
1646 
1647 bool GazeboRosApiPlugin::resetWorld(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
1648 {
1649  world_->ResetEntities(gazebo::physics::Base::MODEL);
1650  return true;
1651 }
1652 
1653 bool GazeboRosApiPlugin::pausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
1654 {
1655  world_->SetPaused(true);
1656  return true;
1657 }
1658 
1659 bool GazeboRosApiPlugin::unpausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res)
1660 {
1661  world_->SetPaused(false);
1662  return true;
1663 }
1664 
1665 bool GazeboRosApiPlugin::clearJointForces(gazebo_msgs::JointRequest::Request &req,
1666  gazebo_msgs::JointRequest::Response &res)
1667 {
1668  return clearJointForces(req.joint_name);
1669 }
1670 bool GazeboRosApiPlugin::clearJointForces(std::string joint_name)
1671 {
1672  bool search = true;
1673  lock_.lock();
1674  while(search)
1675  {
1676  search = false;
1677  for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();++iter)
1678  {
1679  if ((*iter)->joint->GetName() == joint_name)
1680  {
1681  // found one, search through again
1682  search = true;
1683  delete (*iter);
1684  force_joint_jobs_.erase(iter);
1685  break;
1686  }
1687  }
1688  }
1689  lock_.unlock();
1690  return true;
1691 }
1692 
1693 bool GazeboRosApiPlugin::clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req,
1694  gazebo_msgs::BodyRequest::Response &res)
1695 {
1696  return clearBodyWrenches(req.body_name);
1697 }
1698 bool GazeboRosApiPlugin::clearBodyWrenches(std::string body_name)
1699 {
1700  bool search = true;
1701  lock_.lock();
1702  while(search)
1703  {
1704  search = false;
1705  for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();++iter)
1706  {
1707  //ROS_ERROR_NAMED("api_plugin", "search %s %s",(*iter)->body->GetScopedName().c_str(), body_name.c_str());
1708  if ((*iter)->body->GetScopedName() == body_name)
1709  {
1710  // found one, search through again
1711  search = true;
1712  delete (*iter);
1713  wrench_body_jobs_.erase(iter);
1714  break;
1715  }
1716  }
1717  }
1718  lock_.unlock();
1719  return true;
1720 }
1721 
1722 bool GazeboRosApiPlugin::setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req,
1723  gazebo_msgs::SetModelConfiguration::Response &res)
1724 {
1725  std::string gazebo_model_name = req.model_name;
1726 
1727  // search for model with name
1728 #if GAZEBO_MAJOR_VERSION >= 8
1729  gazebo::physics::ModelPtr gazebo_model = world_->ModelByName(req.model_name);
1730 #else
1731  gazebo::physics::ModelPtr gazebo_model = world_->GetModel(req.model_name);
1732 #endif
1733  if (!gazebo_model)
1734  {
1735  ROS_ERROR_NAMED("api_plugin", "SetModelConfiguration: model [%s] does not exist",gazebo_model_name.c_str());
1736  res.success = false;
1737  res.status_message = "SetModelConfiguration: model does not exist";
1738  return true;
1739  }
1740 
1741  if (req.joint_names.size() == req.joint_positions.size())
1742  {
1743  std::map<std::string, double> joint_position_map;
1744  for (unsigned int i = 0; i < req.joint_names.size(); i++)
1745  {
1746  joint_position_map[req.joint_names[i]] = req.joint_positions[i];
1747  }
1748 
1749  // make the service call to pause gazebo
1750  bool is_paused = world_->IsPaused();
1751  if (!is_paused) world_->SetPaused(true);
1752 
1753  gazebo_model->SetJointPositions(joint_position_map);
1754 
1755  // resume paused state before this call
1756  world_->SetPaused(is_paused);
1757 
1758  res.success = true;
1759  res.status_message = "SetModelConfiguration: success";
1760  return true;
1761  }
1762  else
1763  {
1764  res.success = false;
1765  res.status_message = "SetModelConfiguration: joint name and position list have different lengths";
1766  return true;
1767  }
1768 }
1769 
1770 bool GazeboRosApiPlugin::setLinkState(gazebo_msgs::SetLinkState::Request &req,
1771  gazebo_msgs::SetLinkState::Response &res)
1772 {
1773 #if GAZEBO_MAJOR_VERSION >= 8
1774  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->EntityByName(req.link_state.link_name));
1775  gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->EntityByName(req.link_state.reference_frame));
1776 #else
1777  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_state.link_name));
1778  gazebo::physics::EntityPtr frame = world_->GetEntity(req.link_state.reference_frame);
1779 #endif
1780  if (!body)
1781  {
1782  ROS_ERROR_NAMED("api_plugin", "Updating LinkState: link [%s] does not exist",req.link_state.link_name.c_str());
1783  res.success = false;
1784  res.status_message = "SetLinkState: link does not exist";
1785  return true;
1786  }
1787 
1789  // get reference frame (body/model(link)) pose and
1790  // transform target pose to absolute world frame
1791  ignition::math::Vector3d target_pos(req.link_state.pose.position.x,req.link_state.pose.position.y,req.link_state.pose.position.z);
1792  ignition::math::Quaterniond 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);
1793  ignition::math::Pose3d target_pose(target_pos,target_rot);
1794  ignition::math::Vector3d target_linear_vel(req.link_state.twist.linear.x,req.link_state.twist.linear.y,req.link_state.twist.linear.z);
1795  ignition::math::Vector3d target_angular_vel(req.link_state.twist.angular.x,req.link_state.twist.angular.y,req.link_state.twist.angular.z);
1796 
1797  if (frame)
1798  {
1799 #if GAZEBO_MAJOR_VERSION >= 8
1800  ignition::math::Pose3d frame_pose = frame->WorldPose(); // - myBody->GetCoMPose();
1801  ignition::math::Vector3d frame_linear_vel = frame->WorldLinearVel();
1802  ignition::math::Vector3d frame_angular_vel = frame->WorldAngularVel();
1803 #else
1804  ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign(); // - myBody->GetCoMPose();
1805  ignition::math::Vector3d frame_linear_vel = frame->GetWorldLinearVel().Ign();
1806  ignition::math::Vector3d frame_angular_vel = frame->GetWorldAngularVel().Ign();
1807 #endif
1808  ignition::math::Vector3d frame_pos = frame_pose.Pos();
1809  ignition::math::Quaterniond frame_rot = frame_pose.Rot();
1810 
1811  //std::cout << " debug : " << frame->GetName() << " : " << frame_pose << " : " << target_pose << std::endl;
1812  target_pose = target_pose + frame_pose;
1813 
1814  target_linear_vel -= frame_linear_vel;
1815  target_angular_vel -= frame_angular_vel;
1816  }
1817  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")
1818  {
1819  ROS_INFO_NAMED("api_plugin", "Updating LinkState: reference_frame is empty/world/map, using inertial frame");
1820  }
1821  else
1822  {
1823  ROS_ERROR_NAMED("api_plugin", "Updating LinkState: reference_frame is not a valid entity name");
1824  res.success = false;
1825  res.status_message = "SetLinkState: failed";
1826  return true;
1827  }
1828 
1829  //std::cout << " debug : " << target_pose << std::endl;
1830  //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
1831 
1832  bool is_paused = world_->IsPaused();
1833  if (!is_paused) world_->SetPaused(true);
1834  body->SetWorldPose(target_pose);
1835  world_->SetPaused(is_paused);
1836 
1837  // set body velocity to desired twist
1838  body->SetLinearVel(target_linear_vel);
1839  body->SetAngularVel(target_angular_vel);
1840 
1841  res.success = true;
1842  res.status_message = "SetLinkState: success";
1843  return true;
1844 }
1845 
1846 void GazeboRosApiPlugin::updateLinkState(const gazebo_msgs::LinkState::ConstPtr& link_state)
1847 {
1848  gazebo_msgs::SetLinkState::Request req;
1849  gazebo_msgs::SetLinkState::Response res;
1850  req.link_state = *link_state;
1851  /*bool success = */ setLinkState(req,res);
1852 }
1853 
1854 void GazeboRosApiPlugin::transformWrench( ignition::math::Vector3d &target_force, ignition::math::Vector3d &target_torque,
1855  const ignition::math::Vector3d &reference_force,
1856  const ignition::math::Vector3d &reference_torque,
1857  const ignition::math::Pose3d &target_to_reference )
1858 {
1859  // rotate force into target frame
1860  target_force = target_to_reference.Rot().RotateVector(reference_force);
1861  // rotate torque into target frame
1862  target_torque = target_to_reference.Rot().RotateVector(reference_torque);
1863 
1864  // target force is the refence force rotated by the target->reference transform
1865  target_torque = target_torque + target_to_reference.Pos().Cross(target_force);
1866 }
1867 
1868 bool GazeboRosApiPlugin::applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req,
1869  gazebo_msgs::ApplyBodyWrench::Response &res)
1870 {
1871 #if GAZEBO_MAJOR_VERSION >= 8
1872  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->EntityByName(req.body_name));
1873  gazebo::physics::EntityPtr frame = world_->EntityByName(req.reference_frame);
1874 #else
1875  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.body_name));
1876  gazebo::physics::EntityPtr frame = world_->GetEntity(req.reference_frame);
1877 #endif
1878  if (!body)
1879  {
1880  ROS_ERROR_NAMED("api_plugin", "ApplyBodyWrench: body [%s] does not exist",req.body_name.c_str());
1881  res.success = false;
1882  res.status_message = "ApplyBodyWrench: body does not exist";
1883  return true;
1884  }
1885 
1886  // target wrench
1887  ignition::math::Vector3d reference_force(req.wrench.force.x,req.wrench.force.y,req.wrench.force.z);
1888  ignition::math::Vector3d reference_torque(req.wrench.torque.x,req.wrench.torque.y,req.wrench.torque.z);
1889  ignition::math::Vector3d reference_point(req.reference_point.x,req.reference_point.y,req.reference_point.z);
1890 
1891  ignition::math::Vector3d target_force;
1892  ignition::math::Vector3d target_torque;
1893 
1896  reference_torque = reference_torque + reference_point.Cross(reference_force);
1897 
1899  if (frame)
1900  {
1901  // get reference frame (body/model(body)) pose and
1902  // transform target pose to absolute world frame
1903  // @todo: need to modify wrench (target force and torque by frame)
1904  // transform wrench from reference_point in reference_frame
1905  // into the reference frame of the body
1906  // first, translate by reference point to the body frame
1907 #if GAZEBO_MAJOR_VERSION >= 8
1908  ignition::math::Pose3d framePose = frame->WorldPose();
1909  ignition::math::Pose3d bodyPose = body->WorldPose();
1910 #else
1911  ignition::math::Pose3d framePose = frame->GetWorldPose().Ign();
1912  ignition::math::Pose3d bodyPose = body->GetWorldPose().Ign();
1913 #endif
1914  ignition::math::Pose3d target_to_reference = framePose - bodyPose;
1915  ROS_DEBUG_NAMED("api_plugin", "reference frame for applied wrench: [%f %f %f, %f %f %f]-[%f %f %f, %f %f %f]=[%f %f %f, %f %f %f]",
1916  bodyPose.Pos().X(),
1917  bodyPose.Pos().Y(),
1918  bodyPose.Pos().Z(),
1919  bodyPose.Rot().Euler().X(),
1920  bodyPose.Rot().Euler().Y(),
1921  bodyPose.Rot().Euler().Z(),
1922  framePose.Pos().X(),
1923  framePose.Pos().Y(),
1924  framePose.Pos().Z(),
1925  framePose.Rot().Euler().X(),
1926  framePose.Rot().Euler().Y(),
1927  framePose.Rot().Euler().Z(),
1928  target_to_reference.Pos().X(),
1929  target_to_reference.Pos().Y(),
1930  target_to_reference.Pos().Z(),
1931  target_to_reference.Rot().Euler().X(),
1932  target_to_reference.Rot().Euler().Y(),
1933  target_to_reference.Rot().Euler().Z()
1934  );
1935  transformWrench(target_force, target_torque, reference_force, reference_torque, target_to_reference);
1936  ROS_ERROR_NAMED("api_plugin", "wrench defined as [%s]:[%f %f %f, %f %f %f] --> applied as [%s]:[%f %f %f, %f %f %f]",
1937  frame->GetName().c_str(),
1938  reference_force.X(),
1939  reference_force.Y(),
1940  reference_force.Z(),
1941  reference_torque.X(),
1942  reference_torque.Y(),
1943  reference_torque.Z(),
1944  body->GetName().c_str(),
1945  target_force.X(),
1946  target_force.Y(),
1947  target_force.Z(),
1948  target_torque.X(),
1949  target_torque.Y(),
1950  target_torque.Z()
1951  );
1952 
1953  }
1954  else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
1955  {
1956  ROS_INFO_NAMED("api_plugin", "ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame");
1957  // FIXME: transfer to inertial frame
1958 #if GAZEBO_MAJOR_VERSION >= 8
1959  ignition::math::Pose3d target_to_reference = body->WorldPose();
1960 #else
1961  ignition::math::Pose3d target_to_reference = body->GetWorldPose().Ign();
1962 #endif
1963  target_force = reference_force;
1964  target_torque = reference_torque;
1965 
1966  }
1967  else
1968  {
1969  ROS_ERROR_NAMED("api_plugin", "ApplyBodyWrench: reference_frame is not a valid entity name");
1970  res.success = false;
1971  res.status_message = "ApplyBodyWrench: reference_frame not found";
1972  return true;
1973  }
1974 
1975  // apply wrench
1976  // schedule a job to do below at appropriate times:
1977  // body->SetForce(force)
1978  // body->SetTorque(torque)
1980  wej->body = body;
1981  wej->force = target_force;
1982  wej->torque = target_torque;
1983  wej->start_time = req.start_time;
1984 #if GAZEBO_MAJOR_VERSION >= 8
1985  if (wej->start_time < ros::Time(world_->SimTime().Double()))
1986  wej->start_time = ros::Time(world_->SimTime().Double());
1987 #else
1988  if (wej->start_time < ros::Time(world_->GetSimTime().Double()))
1989  wej->start_time = ros::Time(world_->GetSimTime().Double());
1990 #endif
1991  wej->duration = req.duration;
1992  lock_.lock();
1993  wrench_body_jobs_.push_back(wej);
1994  lock_.unlock();
1995 
1996  res.success = true;
1997  res.status_message = "";
1998  return true;
1999 }
2000 
2001 bool GazeboRosApiPlugin::isURDF(std::string model_xml)
2002 {
2003  TiXmlDocument doc_in;
2004  doc_in.Parse(model_xml.c_str());
2005  if (doc_in.FirstChild("robot"))
2006  return true;
2007  else
2008  return false;
2009 }
2010 
2011 bool GazeboRosApiPlugin::isSDF(std::string model_xml)
2012 {
2013  // FIXME: very crude check
2014  TiXmlDocument doc_in;
2015  doc_in.Parse(model_xml.c_str());
2016  if (doc_in.FirstChild("gazebo") ||
2017  doc_in.FirstChild("sdf")) // sdf
2018  return true;
2019  else
2020  return false;
2021 }
2022 
2024 {
2025  // MDMutex locks in case model is getting deleted, don't have to do this if we delete jobs first
2026  // boost::recursive_mutex::scoped_lock lock(*world->GetMDMutex());
2027  lock_.lock();
2028  for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();)
2029  {
2030  // check times and apply wrench if necessary
2031 #if GAZEBO_MAJOR_VERSION >= 8
2032  ros::Time simTime = ros::Time(world_->SimTime().Double());
2033 #else
2034  ros::Time simTime = ros::Time(world_->GetSimTime().Double());
2035 #endif
2036  if (simTime >= (*iter)->start_time)
2037  if (simTime <= (*iter)->start_time+(*iter)->duration ||
2038  (*iter)->duration.toSec() < 0.0)
2039  {
2040  if ((*iter)->body) // if body exists
2041  {
2042  (*iter)->body->SetForce((*iter)->force);
2043  (*iter)->body->SetTorque((*iter)->torque);
2044  }
2045  else
2046  (*iter)->duration.fromSec(0.0); // mark for delete
2047  }
2048 
2049  if (simTime > (*iter)->start_time+(*iter)->duration &&
2050  (*iter)->duration.toSec() >= 0.0)
2051  {
2052  // remove from queue once expires
2053  delete (*iter);
2054  iter = wrench_body_jobs_.erase(iter);
2055  }
2056  else
2057  ++iter;
2058  }
2059  lock_.unlock();
2060 }
2061 
2063 {
2064  // MDMutex locks in case model is getting deleted, don't have to do this if we delete jobs first
2065  // boost::recursive_mutex::scoped_lock lock(*world->GetMDMutex());
2066  lock_.lock();
2067  for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();)
2068  {
2069  // check times and apply force if necessary
2070 #if GAZEBO_MAJOR_VERSION >= 8
2071  ros::Time simTime = ros::Time(world_->SimTime().Double());
2072 #else
2073  ros::Time simTime = ros::Time(world_->GetSimTime().Double());
2074 #endif
2075  if (simTime >= (*iter)->start_time)
2076  if (simTime <= (*iter)->start_time+(*iter)->duration ||
2077  (*iter)->duration.toSec() < 0.0)
2078  {
2079  if ((*iter)->joint) // if joint exists
2080  (*iter)->joint->SetForce(0,(*iter)->force);
2081  else
2082  (*iter)->duration.fromSec(0.0); // mark for delete
2083  }
2084 
2085  if (simTime > (*iter)->start_time+(*iter)->duration &&
2086  (*iter)->duration.toSec() >= 0.0)
2087  {
2088  // remove from queue once expires
2089  iter = force_joint_jobs_.erase(iter);
2090  }
2091  else
2092  ++iter;
2093  }
2094  lock_.unlock();
2095 }
2096 
2098 {
2099  ROS_ERROR_NAMED("api_plugin", "CLOCK2");
2100 #if GAZEBO_MAJOR_VERSION >= 8
2101  gazebo::common::Time sim_time = world_->SimTime();
2102 #else
2103  gazebo::common::Time sim_time = world_->GetSimTime();
2104 #endif
2105  if (pub_clock_frequency_ > 0 && (sim_time - last_pub_clock_time_).Double() < 1.0/pub_clock_frequency_)
2106  return;
2107 
2108  gazebo::common::Time currentTime = gazebo::msgs::Convert( msg->sim_time() );
2109  rosgraph_msgs::Clock ros_time_;
2110  ros_time_.clock.fromSec(currentTime.Double());
2111  // publish time to ros
2112  last_pub_clock_time_ = sim_time;
2113  pub_clock_.publish(ros_time_);
2114 }
2116 {
2117 #if GAZEBO_MAJOR_VERSION >= 8
2118  gazebo::common::Time sim_time = world_->SimTime();
2119 #else
2120  gazebo::common::Time sim_time = world_->GetSimTime();
2121 #endif
2122  if (pub_clock_frequency_ > 0 && (sim_time - last_pub_clock_time_).Double() < 1.0/pub_clock_frequency_)
2123  return;
2124 
2125 #if GAZEBO_MAJOR_VERSION >= 8
2126  gazebo::common::Time currentTime = world_->SimTime();
2127 #else
2128  gazebo::common::Time currentTime = world_->GetSimTime();
2129 #endif
2130  rosgraph_msgs::Clock ros_time_;
2131  ros_time_.clock.fromSec(currentTime.Double());
2132  // publish time to ros
2133  last_pub_clock_time_ = sim_time;
2134  pub_clock_.publish(ros_time_);
2135 }
2136 
2138 {
2139  gazebo_msgs::LinkStates link_states;
2140 
2141  // fill link_states
2142 #if GAZEBO_MAJOR_VERSION >= 8
2143  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
2144  {
2145  gazebo::physics::ModelPtr model = world_->ModelByIndex(i);
2146 #else
2147  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
2148  {
2149  gazebo::physics::ModelPtr model = world_->GetModel(i);
2150 #endif
2151 
2152  for (unsigned int j = 0 ; j < model->GetChildCount(); j ++)
2153  {
2154  gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(j));
2155 
2156  if (body)
2157  {
2158  link_states.name.push_back(body->GetScopedName());
2159  geometry_msgs::Pose pose;
2160 #if GAZEBO_MAJOR_VERSION >= 8
2161  ignition::math::Pose3d body_pose = body->WorldPose(); // - myBody->GetCoMPose();
2162  ignition::math::Vector3d linear_vel = body->WorldLinearVel();
2163  ignition::math::Vector3d angular_vel = body->WorldAngularVel();
2164 #else
2165  ignition::math::Pose3d body_pose = body->GetWorldPose().Ign(); // - myBody->GetCoMPose();
2166  ignition::math::Vector3d linear_vel = body->GetWorldLinearVel().Ign();
2167  ignition::math::Vector3d angular_vel = body->GetWorldAngularVel().Ign();
2168 #endif
2169  ignition::math::Vector3d pos = body_pose.Pos();
2170  ignition::math::Quaterniond rot = body_pose.Rot();
2171  pose.position.x = pos.X();
2172  pose.position.y = pos.Y();
2173  pose.position.z = pos.Z();
2174  pose.orientation.w = rot.W();
2175  pose.orientation.x = rot.X();
2176  pose.orientation.y = rot.Y();
2177  pose.orientation.z = rot.Z();
2178  link_states.pose.push_back(pose);
2179  geometry_msgs::Twist twist;
2180  twist.linear.x = linear_vel.X();
2181  twist.linear.y = linear_vel.Y();
2182  twist.linear.z = linear_vel.Z();
2183  twist.angular.x = angular_vel.X();
2184  twist.angular.y = angular_vel.Y();
2185  twist.angular.z = angular_vel.Z();
2186  link_states.twist.push_back(twist);
2187  }
2188  }
2189  }
2190 
2191  pub_link_states_.publish(link_states);
2192 }
2193 
2195 {
2196  gazebo_msgs::ModelStates model_states;
2197 
2198  // fill model_states
2199 #if GAZEBO_MAJOR_VERSION >= 8
2200  for (unsigned int i = 0; i < world_->ModelCount(); i ++)
2201  {
2202  gazebo::physics::ModelPtr model = world_->ModelByIndex(i);
2203  ignition::math::Pose3d model_pose = model->WorldPose(); // - myBody->GetCoMPose();
2204  ignition::math::Vector3d linear_vel = model->WorldLinearVel();
2205  ignition::math::Vector3d angular_vel = model->WorldAngularVel();
2206 #else
2207  for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
2208  {
2209  gazebo::physics::ModelPtr model = world_->GetModel(i);
2210  ignition::math::Pose3d model_pose = model->GetWorldPose().Ign(); // - myBody->GetCoMPose();
2211  ignition::math::Vector3d linear_vel = model->GetWorldLinearVel().Ign();
2212  ignition::math::Vector3d angular_vel = model->GetWorldAngularVel().Ign();
2213 #endif
2214  ignition::math::Vector3d pos = model_pose.Pos();
2215  ignition::math::Quaterniond rot = model_pose.Rot();
2216  geometry_msgs::Pose pose;
2217  pose.position.x = pos.X();
2218  pose.position.y = pos.Y();
2219  pose.position.z = pos.Z();
2220  pose.orientation.w = rot.W();
2221  pose.orientation.x = rot.X();
2222  pose.orientation.y = rot.Y();
2223  pose.orientation.z = rot.Z();
2224  model_states.pose.push_back(pose);
2225  model_states.name.push_back(model->GetName());
2226  geometry_msgs::Twist twist;
2227  twist.linear.x = linear_vel.X();
2228  twist.linear.y = linear_vel.Y();
2229  twist.linear.z = linear_vel.Z();
2230  twist.angular.x = angular_vel.X();
2231  twist.angular.y = angular_vel.Y();
2232  twist.angular.z = angular_vel.Z();
2233  model_states.twist.push_back(twist);
2234  }
2235  pub_model_states_.publish(model_states);
2236 }
2237 
2238 void GazeboRosApiPlugin::physicsReconfigureCallback(gazebo_ros::PhysicsConfig &config, uint32_t level)
2239 {
2241  {
2242  gazebo_msgs::GetPhysicsProperties srv;
2244 
2245  config.time_step = srv.response.time_step;
2246  config.max_update_rate = srv.response.max_update_rate;
2247  config.gravity_x = srv.response.gravity.x;
2248  config.gravity_y = srv.response.gravity.y;
2249  config.gravity_z = srv.response.gravity.z;
2250  config.auto_disable_bodies = srv.response.ode_config.auto_disable_bodies;
2251  config.sor_pgs_precon_iters = srv.response.ode_config.sor_pgs_precon_iters;
2252  config.sor_pgs_iters = srv.response.ode_config.sor_pgs_iters;
2253  config.sor_pgs_rms_error_tol = srv.response.ode_config.sor_pgs_rms_error_tol;
2254  config.sor_pgs_w = srv.response.ode_config.sor_pgs_w;
2255  config.contact_surface_layer = srv.response.ode_config.contact_surface_layer;
2256  config.contact_max_correcting_vel = srv.response.ode_config.contact_max_correcting_vel;
2257  config.cfm = srv.response.ode_config.cfm;
2258  config.erp = srv.response.ode_config.erp;
2259  config.max_contacts = srv.response.ode_config.max_contacts;
2261  }
2262  else
2263  {
2264  bool changed = false;
2265  gazebo_msgs::GetPhysicsProperties srv;
2267 
2268  // check for changes
2269  if (config.time_step != srv.response.time_step) changed = true;
2270  if (config.max_update_rate != srv.response.max_update_rate) changed = true;
2271  if (config.gravity_x != srv.response.gravity.x) changed = true;
2272  if (config.gravity_y != srv.response.gravity.y) changed = true;
2273  if (config.gravity_z != srv.response.gravity.z) changed = true;
2274  if (config.auto_disable_bodies != srv.response.ode_config.auto_disable_bodies) changed = true;
2275  if ((uint32_t)config.sor_pgs_precon_iters != srv.response.ode_config.sor_pgs_precon_iters) changed = true;
2276  if ((uint32_t)config.sor_pgs_iters != srv.response.ode_config.sor_pgs_iters) changed = true;
2277  if (config.sor_pgs_rms_error_tol != srv.response.ode_config.sor_pgs_rms_error_tol) changed = true;
2278  if (config.sor_pgs_w != srv.response.ode_config.sor_pgs_w) changed = true;
2279  if (config.contact_surface_layer != srv.response.ode_config.contact_surface_layer) changed = true;
2280  if (config.contact_max_correcting_vel != srv.response.ode_config.contact_max_correcting_vel) changed = true;
2281  if (config.cfm != srv.response.ode_config.cfm) changed = true;
2282  if (config.erp != srv.response.ode_config.erp) changed = true;
2283  if ((uint32_t)config.max_contacts != srv.response.ode_config.max_contacts) changed = true;
2284 
2285  if (changed)
2286  {
2287  // pause simulation if requested
2288  gazebo_msgs::SetPhysicsProperties srv;
2289  srv.request.time_step = config.time_step ;
2290  srv.request.max_update_rate = config.max_update_rate ;
2291  srv.request.gravity.x = config.gravity_x ;
2292  srv.request.gravity.y = config.gravity_y ;
2293  srv.request.gravity.z = config.gravity_z ;
2294  srv.request.ode_config.auto_disable_bodies = config.auto_disable_bodies ;
2295  srv.request.ode_config.sor_pgs_precon_iters = config.sor_pgs_precon_iters ;
2296  srv.request.ode_config.sor_pgs_iters = config.sor_pgs_iters ;
2297  srv.request.ode_config.sor_pgs_rms_error_tol = config.sor_pgs_rms_error_tol ;
2298  srv.request.ode_config.sor_pgs_w = config.sor_pgs_w ;
2299  srv.request.ode_config.contact_surface_layer = config.contact_surface_layer ;
2300  srv.request.ode_config.contact_max_correcting_vel = config.contact_max_correcting_vel ;
2301  srv.request.ode_config.cfm = config.cfm ;
2302  srv.request.ode_config.erp = config.erp ;
2303  srv.request.ode_config.max_contacts = config.max_contacts ;
2305  ROS_INFO_NAMED("api_plugin", "physics dynamics reconfigure update complete");
2306  }
2307  ROS_INFO_NAMED("api_plugin", "physics dynamics reconfigure complete");
2308  }
2309 }
2310 
2312 {
2313  physics_reconfigure_set_client_ = nh_->serviceClient<gazebo_msgs::SetPhysicsProperties>("/gazebo/set_physics_properties");
2314  physics_reconfigure_get_client_ = nh_->serviceClient<gazebo_msgs::GetPhysicsProperties>("/gazebo/get_physics_properties");
2315 
2316  // Wait until the rest of this plugin is loaded and the services are being offered
2318  physics_reconfigure_get_client_.waitForExistence();
2319 
2320  physics_reconfigure_srv_.reset(new dynamic_reconfigure::Server<gazebo_ros::PhysicsConfig>());
2321 
2324 
2325  ROS_INFO_NAMED("api_plugin", "Physics dynamic reconfigure ready.");
2326 }
2327 
2328 void GazeboRosApiPlugin::stripXmlDeclaration(std::string &model_xml)
2329 {
2330  // incoming robot model string is a string containing a Gazebo Model XML
2334  std::string open_bracket("<?");
2335  std::string close_bracket("?>");
2336  size_t pos1 = model_xml.find(open_bracket,0);
2337  size_t pos2 = model_xml.find(close_bracket,0);
2338  if (pos1 != std::string::npos && pos2 != std::string::npos)
2339  model_xml.replace(pos1,pos2-pos1+2,std::string(""));
2340 }
2341 
2342 void GazeboRosApiPlugin::updateSDFAttributes(TiXmlDocument &gazebo_model_xml,
2343  const std::string &model_name,
2344  const ignition::math::Vector3d &initial_xyz,
2345  const ignition::math::Quaterniond &initial_q)
2346 {
2347  // This function can handle both regular SDF files and <include> SDFs that are used with the
2348  // Gazebo Model Database
2349 
2350  TiXmlElement* pose_element; // This is used by both reguar and database SDFs
2351 
2352  // Check SDF for requires SDF element
2353  TiXmlElement* gazebo_tixml = gazebo_model_xml.FirstChildElement("sdf");
2354  if (!gazebo_tixml)
2355  {
2356  ROS_WARN_NAMED("api_plugin", "Could not find <sdf> element in sdf, so name and initial position cannot be applied");
2357  return;
2358  }
2359 
2360  // Check SDF for optional model element. May not have one
2361  TiXmlElement* model_tixml = gazebo_tixml->FirstChildElement("model");
2362  if (model_tixml)
2363  {
2364  // Update entity name
2365  if (model_tixml->Attribute("name") != NULL)
2366  {
2367  // removing old entity name
2368  model_tixml->RemoveAttribute("name");
2369  }
2370  // replace with user specified name
2371  model_tixml->SetAttribute("name",model_name);
2372  }
2373  else
2374  {
2375  // Check SDF for world element
2376  TiXmlElement* world_tixml = gazebo_tixml->FirstChildElement("world");
2377  if (!world_tixml)
2378  {
2379  ROS_WARN_NAMED("api_plugin", "Could not find <model> or <world> element in sdf, so name and initial position cannot be applied");
2380  return;
2381  }
2382  // If not <model> element, check SDF for required include element
2383  model_tixml = world_tixml->FirstChildElement("include");
2384  if (!model_tixml)
2385  {
2386  ROS_WARN_NAMED("api_plugin", "Could not find <include> element in sdf, so name and initial position cannot be applied");
2387  return;
2388  }
2389 
2390  // Check for name element
2391  TiXmlElement* name_tixml = model_tixml->FirstChildElement("name");
2392  if (!name_tixml)
2393  {
2394  // Create the name element
2395  name_tixml = new TiXmlElement("name");
2396  model_tixml->LinkEndChild(name_tixml);
2397  }
2398 
2399  // Set the text within the name element
2400  TiXmlText* text = new TiXmlText(model_name);
2401  name_tixml->LinkEndChild( text );
2402  }
2403 
2404 
2405  // Check for the pose element
2406  pose_element = model_tixml->FirstChildElement("pose");
2407  ignition::math::Pose3d model_pose;
2408 
2409  // Create the pose element if it doesn't exist
2410  // Remove it if it exists, since we are inserting a new one
2411  if (pose_element)
2412  {
2413  // save pose_element in ignition::math::Pose3d and remove child
2414  model_pose = this->parsePose(pose_element->GetText());
2415  model_tixml->RemoveChild(pose_element);
2416  }
2417 
2418  // Set and link the pose element after adding initial pose
2419  {
2420  // add pose_element Pose to initial pose
2421  ignition::math::Pose3d new_model_pose = model_pose + ignition::math::Pose3d(initial_xyz, initial_q);
2422 
2423  // Create the string of 6 numbers
2424  std::ostringstream pose_stream;
2425  ignition::math::Vector3d model_rpy = new_model_pose.Rot().Euler(); // convert to Euler angles for Gazebo XML
2426  pose_stream << new_model_pose.Pos().X() << " " << new_model_pose.Pos().Y() << " " << new_model_pose.Pos().Z() << " "
2427  << model_rpy.X() << " " << model_rpy.Y() << " " << model_rpy.Z();
2428 
2429  // Add value to pose element
2430  TiXmlText* text = new TiXmlText(pose_stream.str());
2431  TiXmlElement* new_pose_element = new TiXmlElement("pose");
2432  new_pose_element->LinkEndChild(text);
2433  model_tixml->LinkEndChild(new_pose_element);
2434  }
2435 }
2436 
2437 ignition::math::Pose3d GazeboRosApiPlugin::parsePose(const std::string &str)
2438 {
2439  std::vector<std::string> pieces;
2440  std::vector<double> vals;
2441 
2442  boost::split(pieces, str, boost::is_any_of(" "));
2443  for (unsigned int i = 0; i < pieces.size(); ++i)
2444  {
2445  if (pieces[i] != "")
2446  {
2447  try
2448  {
2449  vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2450  }
2451  catch(boost::bad_lexical_cast &e)
2452  {
2453  sdferr << "xml key [" << str
2454  << "][" << i << "] value [" << pieces[i]
2455  << "] is not a valid double from a 3-tuple\n";
2456  return ignition::math::Pose3d();
2457  }
2458  }
2459  }
2460 
2461  if (vals.size() == 6)
2462  return ignition::math::Pose3d(vals[0], vals[1], vals[2], vals[3], vals[4], vals[5]);
2463  else
2464  {
2465  ROS_ERROR_NAMED("api_plugin", "Beware: failed to parse string [%s] as ignition::math::Pose3d, returning zeros.", str.c_str());
2466  return ignition::math::Pose3d();
2467  }
2468 }
2469 
2470 ignition::math::Vector3d GazeboRosApiPlugin::parseVector3(const std::string &str)
2471 {
2472  std::vector<std::string> pieces;
2473  std::vector<double> vals;
2474 
2475  boost::split(pieces, str, boost::is_any_of(" "));
2476  for (unsigned int i = 0; i < pieces.size(); ++i)
2477  {
2478  if (pieces[i] != "")
2479  {
2480  try
2481  {
2482  vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2483  }
2484  catch(boost::bad_lexical_cast &e)
2485  {
2486  sdferr << "xml key [" << str
2487  << "][" << i << "] value [" << pieces[i]
2488  << "] is not a valid double from a 3-tuple\n";
2489  return ignition::math::Vector3d();
2490  }
2491  }
2492  }
2493 
2494  if (vals.size() == 3)
2495  return ignition::math::Vector3d(vals[0], vals[1], vals[2]);
2496  else
2497  {
2498  ROS_ERROR_NAMED("api_plugin", "Beware: failed to parse string [%s] as ignition::math::Vector3d, returning zeros.", str.c_str());
2499  return ignition::math::Vector3d();
2500  }
2501 }
2502 
2503 void GazeboRosApiPlugin::updateURDFModelPose(TiXmlDocument &gazebo_model_xml,
2504  const ignition::math::Vector3d &initial_xyz,
2505  const ignition::math::Quaterniond &initial_q)
2506 {
2507  TiXmlElement* model_tixml = (gazebo_model_xml.FirstChildElement("robot"));
2508  if (model_tixml)
2509  {
2510  // replace initial pose of model
2511  // find first instance of xyz and rpy, replace with initial pose
2512  TiXmlElement* origin_key = model_tixml->FirstChildElement("origin");
2513 
2514  if (!origin_key)
2515  {
2516  origin_key = new TiXmlElement("origin");
2517  model_tixml->LinkEndChild(origin_key);
2518  }
2519 
2520  ignition::math::Vector3d xyz;
2521  ignition::math::Vector3d rpy;
2522  if (origin_key->Attribute("xyz"))
2523  {
2524  xyz = this->parseVector3(origin_key->Attribute("xyz"));
2525  origin_key->RemoveAttribute("xyz");
2526  }
2527  if (origin_key->Attribute("rpy"))
2528  {
2529  rpy = this->parseVector3(origin_key->Attribute("rpy"));
2530  origin_key->RemoveAttribute("rpy");
2531  }
2532 
2533  // add xyz, rpy to initial pose
2534  ignition::math::Pose3d model_pose = ignition::math::Pose3d(xyz, ignition::math::Quaterniond(rpy))
2535  + ignition::math::Pose3d(initial_xyz, initial_q);
2536 
2537  std::ostringstream xyz_stream;
2538  xyz_stream << model_pose.Pos().X() << " " << model_pose.Pos().Y() << " " << model_pose.Pos().Z();
2539 
2540  std::ostringstream rpy_stream;
2541  ignition::math::Vector3d model_rpy = model_pose.Rot().Euler(); // convert to Euler angles for Gazebo XML
2542  rpy_stream << model_rpy.X() << " " << model_rpy.Y() << " " << model_rpy.Z();
2543 
2544  origin_key->SetAttribute("xyz",xyz_stream.str());
2545  origin_key->SetAttribute("rpy",rpy_stream.str());
2546  }
2547  else
2548  ROS_WARN_NAMED("api_plugin", "Could not find <model> element in sdf, so name and initial position is not applied");
2549 }
2550 
2551 void GazeboRosApiPlugin::updateURDFName(TiXmlDocument &gazebo_model_xml, const std::string &model_name)
2552 {
2553  TiXmlElement* model_tixml = gazebo_model_xml.FirstChildElement("robot");
2554  // replace model name if one is specified by the user
2555  if (model_tixml)
2556  {
2557  if (model_tixml->Attribute("name") != NULL)
2558  {
2559  // removing old model name
2560  model_tixml->RemoveAttribute("name");
2561  }
2562  // replace with user specified name
2563  model_tixml->SetAttribute("name",model_name);
2564  }
2565  else
2566  ROS_WARN_NAMED("api_plugin", "Could not find <robot> element in URDF, name not replaced");
2567 }
2568 
2570 {
2571  TiXmlNode* child = 0;
2572  child = model_xml->IterateChildren(child);
2573  while (child != NULL)
2574  {
2575  if (child->Type() == TiXmlNode::TINYXML_ELEMENT &&
2576  child->ValueStr().compare(std::string("plugin")) == 0)
2577  {
2578  if (child->FirstChildElement("robotNamespace") == NULL)
2579  {
2580  TiXmlElement* child_elem = child->ToElement()->FirstChildElement("robotNamespace");
2581  while (child_elem)
2582  {
2583  child->ToElement()->RemoveChild(child_elem);
2584  child_elem = child->ToElement()->FirstChildElement("robotNamespace");
2585  }
2586  TiXmlElement* key = new TiXmlElement("robotNamespace");
2587  TiXmlText* val = new TiXmlText(robot_namespace_);
2588  key->LinkEndChild(val);
2589  child->ToElement()->LinkEndChild(key);
2590  }
2591  }
2593  child = model_xml->IterateChildren(child);
2594  }
2595 }
2596 
2597 bool GazeboRosApiPlugin::spawnAndConform(TiXmlDocument &gazebo_model_xml, const std::string &model_name,
2598  gazebo_msgs::SpawnModel::Response &res)
2599 {
2600  std::string entity_type = gazebo_model_xml.RootElement()->FirstChild()->Value();
2601  // Convert the entity type to lower case
2602  std::transform(entity_type.begin(), entity_type.end(), entity_type.begin(), ::tolower);
2603 
2604  bool isLight = (entity_type == "light");
2605 
2606  // push to factory iface
2607  std::ostringstream stream;
2608  stream << gazebo_model_xml;
2609  std::string gazebo_model_xml_string = stream.str();
2610  ROS_DEBUG_NAMED("api_plugin.xml", "Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
2611 
2612  // publish to factory topic
2613  gazebo::msgs::Factory msg;
2614  gazebo::msgs::Init(msg, "spawn_model");
2615  msg.set_sdf( gazebo_model_xml_string );
2616 
2617  //ROS_ERROR_NAMED("api_plugin", "attempting to spawn model name [%s] [%s]", model_name.c_str(),gazebo_model_xml_string.c_str());
2618 
2619  // FIXME: should use entity_info or add lock to World::receiveMutex
2620  // looking for Model to see if it exists already
2621  gazebo::msgs::Request *entity_info_msg = gazebo::msgs::CreateRequest("entity_info", model_name);
2622  request_pub_->Publish(*entity_info_msg,true);
2623  // todo: should wait for response response_sub_, check to see that if _msg->response == "nonexistant"
2624 
2625 #if GAZEBO_MAJOR_VERSION >= 8
2626  gazebo::physics::ModelPtr model = world_->ModelByName(model_name);
2627  gazebo::physics::LightPtr light = world_->LightByName(model_name);
2628 #else
2629  gazebo::physics::ModelPtr model = world_->GetModel(model_name);
2630  gazebo::physics::LightPtr light = world_->Light(model_name);
2631 #endif
2632  if ((isLight && light != NULL) || (model != NULL))
2633  {
2634  ROS_ERROR_NAMED("api_plugin", "SpawnModel: Failure - model name %s already exist.",model_name.c_str());
2635  res.success = false;
2636  res.status_message = "SpawnModel: Failure - entity already exists.";
2637  return true;
2638  }
2639 
2640  // for Gazebo 7 and up, use a different method to spawn lights
2641  if (isLight)
2642  {
2643  // Publish the light message to spawn the light (Gazebo 7 and up)
2644  sdf::SDF sdf_light;
2645  sdf_light.SetFromString(gazebo_model_xml_string);
2646  gazebo::msgs::Light msg = gazebo::msgs::LightFromSDF(sdf_light.Root()->GetElement("light"));
2647  msg.set_name(model_name);
2648  factory_light_pub_->Publish(msg);
2649  }
2650  else
2651  {
2652  // Publish the factory message
2653  factory_pub_->Publish(msg);
2654  }
2657 
2659  ros::Duration model_spawn_timeout(10.0);
2660  ros::Time timeout = ros::Time::now() + model_spawn_timeout;
2661 
2662  while (ros::ok())
2663  {
2664  if (ros::Time::now() > timeout)
2665  {
2666  res.success = false;
2667  res.status_message = "SpawnModel: Entity pushed to spawn queue, but spawn service timed out waiting for entity to appear in simulation under the name " + model_name;
2668  return true;
2669  }
2670 
2671  {
2672  //boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
2673 #if GAZEBO_MAJOR_VERSION >= 8
2674  if ((isLight && world_->LightByName(model_name) != NULL)
2675  || (world_->ModelByName(model_name) != NULL))
2676 #else
2677  if ((isLight && world_->Light(model_name) != NULL)
2678  || (world_->GetModel(model_name) != NULL))
2679 #endif
2680  break;
2681  }
2682 
2683  ROS_DEBUG_STREAM_ONCE_NAMED("api_plugin","Waiting for " << timeout - ros::Time::now()
2684  << " for entity " << model_name << " to spawn");
2685 
2686  usleep(2000);
2687  }
2688 
2689  // set result
2690  res.success = true;
2691  res.status_message = "SpawnModel: Successfully spawned entity";
2692  return true;
2693 }
2694 
2695 // Register this plugin with the simulator
2696 GZ_REGISTER_SYSTEM_PLUGIN(GazeboRosApiPlugin)
2697 }
bool getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req, gazebo_msgs::GetLinkProperties::Response &res)
void shutdownSignal()
Detect if sig-int shutdown signal is recieved
#define ROS_DEBUG_ONCE_NAMED(name,...)
ros::ServiceServer reset_simulation_service_
bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req, gazebo_msgs::GetPhysicsProperties::Response &res)
ros::ServiceServer apply_body_wrench_service_
bool setJointProperties(gazebo_msgs::SetJointProperties::Request &req, gazebo_msgs::SetJointProperties::Response &res)
void updateURDFModelPose(TiXmlDocument &gazebo_model_xml, const ignition::math::Vector3d &initial_xyz, const ignition::math::Quaterniond &initial_q)
Update the model pose of the URDF file before sending to Gazebo.
bool setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req, gazebo_msgs::SetPhysicsProperties::Response &res)
gazebo::event::ConnectionPtr time_update_event_
bool setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req, gazebo_msgs::SetModelConfiguration::Response &res)
bool getModelState(gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)
ROSCPP_DECL bool check()
ros::ServiceServer set_physics_properties_service_
ros::ServiceServer get_model_properties_service_
#define ROS_INFO_NAMED(name,...)
ros::ServiceServer unpause_physics_service_
#define ROS_DEBUG_STREAM_NAMED(name, args)
bool setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req, gazebo_msgs::SetLinkProperties::Response &res)
boost::shared_ptr< dynamic_reconfigure::Server< gazebo_ros::PhysicsConfig > > physics_reconfigure_srv_
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
void loadGazeboRosApiPlugin(std::string world_name)
Connect to Gazebo via its plugin interface, get a pointer to the world, start events.
gazebo::common::Time last_pub_clock_time_
ros::ServiceServer spawn_urdf_model_service_
ros::ServiceServer get_light_properties_service_
dynamic_reconfigure::Server< gazebo_ros::PhysicsConfig >::CallbackType physics_reconfigure_callback_
bool isURDF(std::string model_xml)
utility for checking if string is in URDF format
boost::shared_ptr< ros::NodeHandle > nh_
boost::shared_ptr< boost::thread > physics_reconfigure_thread_
ROSCPP_DECL bool isInitialized()
void physicsReconfigureThread()
waits for the rest of Gazebo to be ready before initializing the dynamic reconfigure services ...
bool setLinkState(gazebo_msgs::SetLinkState::Request &req, gazebo_msgs::SetLinkState::Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
gazebo::transport::PublisherPtr request_pub_
ros::ServiceServer clear_body_wrenches_service_
ignition::math::Pose3d parsePose(const std::string &str)
convert xml to Pose
ros::ServiceServer get_link_properties_service_
ros::ServiceServer set_model_configuration_service_
void advertiseServices()
advertise services
gazebo::physics::WorldPtr world_
ros::ServiceClient physics_reconfigure_set_client_
ros::ServiceServer delete_light_service_
bool resetSimulation(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer delete_model_service_
bool unpausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer apply_joint_effort_service_
ros::ServiceServer clear_joint_forces_service_
std::vector< GazeboRosApiPlugin::ForceJointJob * > force_joint_jobs_
std::map< std::string, unsigned int > access_count_get_model_state_
index counters to count the accesses on models via GetModelState
#define ROS_DEBUG_NAMED(name,...)
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
void transformWrench(ignition::math::Vector3d &target_force, ignition::math::Vector3d &target_torque, const ignition::math::Vector3d &reference_force, const ignition::math::Vector3d &reference_torque, const ignition::math::Pose3d &target_to_reference)
helper function for applyBodyWrench shift wrench from reference frame to target frame ...
ros::ServiceServer set_model_state_service_
ros::ServiceClient physics_reconfigure_get_client_
ros::ServiceServer reset_world_service_
bool applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req, gazebo_msgs::ApplyJointEffort::Response &res)
void updateSDFAttributes(TiXmlDocument &gazebo_model_xml, const std::string &model_name, const ignition::math::Vector3d &initial_xyz, const ignition::math::Quaterniond &initial_q)
Update the model name and pose of the SDF file before sending to Gazebo.
bool getJointProperties(gazebo_msgs::GetJointProperties::Request &req, gazebo_msgs::GetJointProperties::Response &res)
ros::ServiceServer get_joint_properties_service_
bool getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req, gazebo_msgs::GetWorldProperties::Response &res)
void updateModelState(const gazebo_msgs::ModelState::ConstPtr &model_state)
gazebo::event::ConnectionPtr sigint_event_
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
gazebo::event::ConnectionPtr pub_model_states_event_
bool deleteLight(gazebo_msgs::DeleteLight::Request &req, gazebo_msgs::DeleteLight::Response &res)
delete a given light by name
gazebo::event::ConnectionPtr wrench_update_event_
void Load(int argc, char **argv)
Gazebo-inherited load function.
gazebo::transport::PublisherPtr factory_light_pub_
bool pausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer set_link_properties_service_
ros::ServiceServer set_light_properties_service_
bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req, gazebo_msgs::BodyRequest::Response &res)
gazebo::transport::SubscriberPtr response_sub_
ROSCPP_DECL bool ok()
bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req, gazebo_msgs::GetModelProperties::Response &res)
boost::shared_ptr< boost::thread > gazebo_callback_queue_thread_
gazebo::event::ConnectionPtr force_update_event_
bool spawnURDFModel(gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
Function for inserting a URDF into Gazebo from ROS Service Call.
void walkChildAddRobotNamespace(TiXmlNode *model_xml)
bool resetWorld(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
#define ROS_DEBUG_STREAM_ONCE_NAMED(name, args)
bool isSDF(std::string model_xml)
utility for checking if string is in SDF format
ROSLIB_DECL std::string getPath(const std::string &package_name)
boost::shared_ptr< ros::AsyncSpinner > async_ros_spin_
A plugin loaded within the gzserver on startup.
bool applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req, gazebo_msgs::ApplyBodyWrench::Response &res)
ros::ServiceServer get_model_state_service_
void physicsReconfigureCallback(gazebo_ros::PhysicsConfig &config, uint32_t level)
Used for the dynamic reconfigure callback function template.
bool clearJointForces(gazebo_msgs::JointRequest::Request &req, gazebo_msgs::JointRequest::Response &res)
ros::ServiceServer set_joint_properties_service_
gazebo::transport::PublisherPtr factory_pub_
gazebo::event::ConnectionPtr load_gazebo_ros_api_plugin_event_
bool spawnAndConform(TiXmlDocument &gazebo_model_xml, const std::string &model_name, gazebo_msgs::SpawnModel::Response &res)
ros::ServiceServer spawn_sdf_model_service_
ignition::math::Vector3d parseVector3(const std::string &str)
convert xml to Pose
bool getLightProperties(gazebo_msgs::GetLightProperties::Request &req, gazebo_msgs::GetLightProperties::Response &res)
ros::ServiceServer get_world_properties_service_
ros::ServiceServer set_link_state_service_
std::vector< GazeboRosApiPlugin::WrenchBodyJob * > wrench_body_jobs_
gazebo::event::ConnectionPtr pub_link_states_event_
Time & fromSec(double t)
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
static Time now()
ros::ServiceServer get_link_state_service_
void updateLinkState(const gazebo_msgs::LinkState::ConstPtr &link_state)
gazebo::transport::NodePtr gazebonode_
void gazeboQueueThread()
ros queue thread for this node
bool setLightProperties(gazebo_msgs::SetLightProperties::Request &req, gazebo_msgs::SetLightProperties::Response &res)
bool deleteModel(gazebo_msgs::DeleteModel::Request &req, gazebo_msgs::DeleteModel::Response &res)
delete model given name
bool spawnSDFModel(gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
Both SDFs and converted URDFs get sent to this function for further manipulation from a ROS Service c...
void onResponse(ConstResponsePtr &response)
Unused.
void stripXmlDeclaration(std::string &model_xml)
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
ros::ServiceServer pause_physics_service_
boost::shared_ptr< void > VoidPtr
bool getLinkState(gazebo_msgs::GetLinkState::Request &req, gazebo_msgs::GetLinkState::Response &res)
void updateURDFName(TiXmlDocument &gazebo_model_xml, const std::string &model_name)
Update the model name of the URDF file before sending to Gazebo.
bool enable_ros_network_
enable the communication of gazebo information using ROS service/topics
ros::ServiceServer get_physics_properties_service_
bool setModelState(gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
gazebo::transport::PublisherPtr light_modify_pub_
#define ROS_WARN_STREAM_NAMED(name, args)


gazebo_ros
Author(s): John Hsu, Nate Koenig, Dave Coleman
autogenerated on Tue Mar 26 2019 02:31:35