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