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


gazebo_ros
Author(s): John Hsu, Nate Koenig, Dave Coleman
autogenerated on Thu Sep 5 2024 02:49:51