-
Notifications
You must be signed in to change notification settings - Fork 773
/
gazebo_ros_api_plugin.cpp
2335 lines (2075 loc) · 97 KB
/
gazebo_ros_api_plugin.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright 2013 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
/* Desc: External interfaces for Gazebo
* Author: Nate Koenig, John Hsu, Dave Coleman
* Date: Jun 10 2013
*/
#include <gazebo/common/Events.hh>
#include <gazebo/gazebo_config.h>
#include <gazebo_ros/gazebo_ros_api_plugin.h>
namespace gazebo
{
GazeboRosApiPlugin::GazeboRosApiPlugin() :
physics_reconfigure_initialized_(false),
world_created_(false),
stop_(false),
plugin_loaded_(false),
pub_link_states_connection_count_(0),
pub_model_states_connection_count_(0),
pub_clock_frequency_(0)
{
robot_namespace_.clear();
}
GazeboRosApiPlugin::~GazeboRosApiPlugin()
{
ROS_DEBUG_STREAM_NAMED("api_plugin","GazeboRosApiPlugin Deconstructor start");
// Unload the sigint event
gazebo::event::Events::DisconnectSigInt(sigint_event_);
ROS_DEBUG_STREAM_NAMED("api_plugin","After sigint_event unload");
// Don't attempt to unload this plugin if it was never loaded in the Load() function
if(!plugin_loaded_)
{
ROS_DEBUG_STREAM_NAMED("api_plugin","Deconstructor skipped because never loaded");
return;
}
// Disconnect slots
gazebo::event::Events::DisconnectWorldCreated(load_gazebo_ros_api_plugin_event_);
gazebo::event::Events::DisconnectWorldUpdateBegin(wrench_update_event_);
gazebo::event::Events::DisconnectWorldUpdateBegin(force_update_event_);
gazebo::event::Events::DisconnectWorldUpdateBegin(time_update_event_);
ROS_DEBUG_STREAM_NAMED("api_plugin","Slots disconnected");
if (pub_link_states_connection_count_ > 0) // disconnect if there are subscribers on exit
gazebo::event::Events::DisconnectWorldUpdateBegin(pub_link_states_event_);
if (pub_model_states_connection_count_ > 0) // disconnect if there are subscribers on exit
gazebo::event::Events::DisconnectWorldUpdateBegin(pub_model_states_event_);
ROS_DEBUG_STREAM_NAMED("api_plugin","Disconnected World Updates");
// Stop the multi threaded ROS spinner
async_ros_spin_->stop();
ROS_DEBUG_STREAM_NAMED("api_plugin","Async ROS Spin Stopped");
// Shutdown the ROS node
nh_->shutdown();
ROS_DEBUG_STREAM_NAMED("api_plugin","Node Handle Shutdown");
// Shutdown ROS queue
gazebo_callback_queue_thread_->join();
ROS_DEBUG_STREAM_NAMED("api_plugin","Callback Queue Joined");
// Physics Dynamic Reconfigure
physics_reconfigure_thread_->join();
ROS_DEBUG_STREAM_NAMED("api_plugin","Physics reconfigure joined");
// Delete Force and Wrench Jobs
lock_.lock();
for (std::vector<GazeboRosApiPlugin::ForceJointJob*>::iterator iter=force_joint_jobs_.begin();iter!=force_joint_jobs_.end();)
{
delete (*iter);
iter = force_joint_jobs_.erase(iter);
}
force_joint_jobs_.clear();
ROS_DEBUG_STREAM_NAMED("api_plugin","ForceJointJobs deleted");
for (std::vector<GazeboRosApiPlugin::WrenchBodyJob*>::iterator iter=wrench_body_jobs_.begin();iter!=wrench_body_jobs_.end();)
{
delete (*iter);
iter = wrench_body_jobs_.erase(iter);
}
wrench_body_jobs_.clear();
lock_.unlock();
ROS_DEBUG_STREAM_NAMED("api_plugin","WrenchBodyJobs deleted");
ROS_DEBUG_STREAM_NAMED("api_plugin","Unloaded");
}
void GazeboRosApiPlugin::shutdownSignal()
{
ROS_DEBUG_STREAM_NAMED("api_plugin","shutdownSignal() recieved");
stop_ = true;
}
void GazeboRosApiPlugin::Load(int argc, char** argv)
{
ROS_DEBUG_STREAM_NAMED("api_plugin","Load");
// connect to sigint event
sigint_event_ = gazebo::event::Events::ConnectSigInt(boost::bind(&GazeboRosApiPlugin::shutdownSignal,this));
// setup ros related
if (!ros::isInitialized())
ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler);
else
ROS_ERROR("Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
// check if the ros master is available - required
while(!ros::master::check())
{
ROS_WARN_STREAM_NAMED("api_plugin","No ROS master - start roscore to continue...");
// wait 0.5 second
usleep(500*1000); // can't use ROS Time here b/c node handle is not yet initialized
if(stop_)
{
ROS_WARN_STREAM_NAMED("api_plugin","Canceled loading Gazebo ROS API plugin by sigint event");
return;
}
}
nh_.reset(new ros::NodeHandle("~")); // advertise topics and services in this node's namespace
// Built-in multi-threaded ROS spinning
async_ros_spin_.reset(new ros::AsyncSpinner(0)); // will use a thread for each CPU core
async_ros_spin_->start();
/// \brief setup custom callback queue
gazebo_callback_queue_thread_.reset(new boost::thread( &GazeboRosApiPlugin::gazeboQueueThread, this) );
/// \brief start a thread for the physics dynamic reconfigure node
physics_reconfigure_thread_.reset(new boost::thread(boost::bind(&GazeboRosApiPlugin::physicsReconfigureThread, this)));
// below needs the world to be created first
load_gazebo_ros_api_plugin_event_ = gazebo::event::Events::ConnectWorldCreated(boost::bind(&GazeboRosApiPlugin::loadGazeboRosApiPlugin,this,_1));
plugin_loaded_ = true;
ROS_INFO("Finished loading Gazebo ROS API Plugin.");
}
void GazeboRosApiPlugin::loadGazeboRosApiPlugin(std::string world_name)
{
// make sure things are only called once
lock_.lock();
if (world_created_)
{
lock_.unlock();
return;
}
// set flag to true and load this plugin
world_created_ = true;
lock_.unlock();
world_ = gazebo::physics::get_world(world_name);
if (!world_)
{
//ROS_ERROR("world name: [%s]",world->GetName().c_str());
// connect helper function to signal for scheduling torque/forces, etc
ROS_FATAL("cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
return;
}
gazebonode_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
gazebonode_->Init(world_name);
//stat_sub_ = gazebonode_->Subscribe("~/world_stats", &GazeboRosApiPlugin::publishSimTime, this); // TODO: does not work in server plugin?
factory_pub_ = gazebonode_->Advertise<gazebo::msgs::Factory>("~/factory");
request_pub_ = gazebonode_->Advertise<gazebo::msgs::Request>("~/request");
response_sub_ = gazebonode_->Subscribe("~/response",&GazeboRosApiPlugin::onResponse, this);
// reset topic connection counts
pub_link_states_connection_count_ = 0;
pub_model_states_connection_count_ = 0;
/// \brief advertise all services
advertiseServices();
// hooks for applying forces, publishing simtime on /clock
wrench_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::wrenchBodySchedulerSlot,this));
force_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::forceJointSchedulerSlot,this));
time_update_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishSimTime,this));
}
void GazeboRosApiPlugin::onResponse(ConstResponsePtr &response)
{
}
void GazeboRosApiPlugin::gazeboQueueThread()
{
static const double timeout = 0.001;
while (nh_->ok())
{
gazebo_queue_.callAvailable(ros::WallDuration(timeout));
}
}
void GazeboRosApiPlugin::advertiseServices()
{
// publish clock for simulated ros time
pub_clock_ = nh_->advertise<rosgraph_msgs::Clock>("/clock",10);
// Advertise spawn services on the custom queue - DEPRECATED IN HYDRO
std::string spawn_gazebo_model_service_name("spawn_gazebo_model");
ros::AdvertiseServiceOptions spawn_gazebo_model_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
spawn_gazebo_model_service_name,
boost::bind(&GazeboRosApiPlugin::spawnGazeboModel,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
spawn_gazebo_model_service_ = nh_->advertiseService(spawn_gazebo_model_aso);
// Advertise spawn services on the custom queue
std::string spawn_sdf_model_service_name("spawn_sdf_model");
ros::AdvertiseServiceOptions spawn_sdf_model_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
spawn_sdf_model_service_name,
boost::bind(&GazeboRosApiPlugin::spawnSDFModel,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
spawn_sdf_model_service_ = nh_->advertiseService(spawn_sdf_model_aso);
// Advertise spawn services on the custom queue
std::string spawn_urdf_model_service_name("spawn_urdf_model");
ros::AdvertiseServiceOptions spawn_urdf_model_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
spawn_urdf_model_service_name,
boost::bind(&GazeboRosApiPlugin::spawnURDFModel,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
spawn_urdf_model_service_ = nh_->advertiseService(spawn_urdf_model_aso);
// Advertise delete services on the custom queue
std::string delete_model_service_name("delete_model");
ros::AdvertiseServiceOptions delete_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
delete_model_service_name,
boost::bind(&GazeboRosApiPlugin::deleteModel,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
delete_model_service_ = nh_->advertiseService(delete_aso);
// Advertise more services on the custom queue
std::string get_model_properties_service_name("get_model_properties");
ros::AdvertiseServiceOptions get_model_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
get_model_properties_service_name,
boost::bind(&GazeboRosApiPlugin::getModelProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_model_properties_service_ = nh_->advertiseService(get_model_properties_aso);
// Advertise more services on the custom queue
std::string get_model_state_service_name("get_model_state");
ros::AdvertiseServiceOptions get_model_state_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
get_model_state_service_name,
boost::bind(&GazeboRosApiPlugin::getModelState,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_model_state_service_ = nh_->advertiseService(get_model_state_aso);
// Advertise more services on the custom queue
std::string get_world_properties_service_name("get_world_properties");
ros::AdvertiseServiceOptions get_world_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
get_world_properties_service_name,
boost::bind(&GazeboRosApiPlugin::getWorldProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_world_properties_service_ = nh_->advertiseService(get_world_properties_aso);
// Advertise more services on the custom queue
std::string get_joint_properties_service_name("get_joint_properties");
ros::AdvertiseServiceOptions get_joint_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
get_joint_properties_service_name,
boost::bind(&GazeboRosApiPlugin::getJointProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_joint_properties_service_ = nh_->advertiseService(get_joint_properties_aso);
// Advertise more services on the custom queue
std::string get_link_properties_service_name("get_link_properties");
ros::AdvertiseServiceOptions get_link_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
get_link_properties_service_name,
boost::bind(&GazeboRosApiPlugin::getLinkProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_link_properties_service_ = nh_->advertiseService(get_link_properties_aso);
// Advertise more services on the custom queue
std::string get_link_state_service_name("get_link_state");
ros::AdvertiseServiceOptions get_link_state_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
get_link_state_service_name,
boost::bind(&GazeboRosApiPlugin::getLinkState,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_link_state_service_ = nh_->advertiseService(get_link_state_aso);
// Advertise more services on the custom queue
std::string get_physics_properties_service_name("get_physics_properties");
ros::AdvertiseServiceOptions get_physics_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
get_physics_properties_service_name,
boost::bind(&GazeboRosApiPlugin::getPhysicsProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
get_physics_properties_service_ = nh_->advertiseService(get_physics_properties_aso);
// publish complete link states in world frame
ros::AdvertiseOptions pub_link_states_ao =
ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
"link_states",10,
boost::bind(&GazeboRosApiPlugin::onLinkStatesConnect,this),
boost::bind(&GazeboRosApiPlugin::onLinkStatesDisconnect,this),
ros::VoidPtr(), &gazebo_queue_);
pub_link_states_ = nh_->advertise(pub_link_states_ao);
// publish complete model states in world frame
ros::AdvertiseOptions pub_model_states_ao =
ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
"model_states",10,
boost::bind(&GazeboRosApiPlugin::onModelStatesConnect,this),
boost::bind(&GazeboRosApiPlugin::onModelStatesDisconnect,this),
ros::VoidPtr(), &gazebo_queue_);
pub_model_states_ = nh_->advertise(pub_model_states_ao);
// Advertise more services on the custom queue
std::string set_link_properties_service_name("set_link_properties");
ros::AdvertiseServiceOptions set_link_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
set_link_properties_service_name,
boost::bind(&GazeboRosApiPlugin::setLinkProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
set_link_properties_service_ = nh_->advertiseService(set_link_properties_aso);
// Advertise more services on the custom queue
std::string set_physics_properties_service_name("set_physics_properties");
ros::AdvertiseServiceOptions set_physics_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
set_physics_properties_service_name,
boost::bind(&GazeboRosApiPlugin::setPhysicsProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
set_physics_properties_service_ = nh_->advertiseService(set_physics_properties_aso);
// Advertise more services on the custom queue
std::string set_model_state_service_name("set_model_state");
ros::AdvertiseServiceOptions set_model_state_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
set_model_state_service_name,
boost::bind(&GazeboRosApiPlugin::setModelState,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
set_model_state_service_ = nh_->advertiseService(set_model_state_aso);
// Advertise more services on the custom queue
std::string set_model_configuration_service_name("set_model_configuration");
ros::AdvertiseServiceOptions set_model_configuration_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
set_model_configuration_service_name,
boost::bind(&GazeboRosApiPlugin::setModelConfiguration,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
set_model_configuration_service_ = nh_->advertiseService(set_model_configuration_aso);
// Advertise more services on the custom queue
std::string set_joint_properties_service_name("set_joint_properties");
ros::AdvertiseServiceOptions set_joint_properties_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
set_joint_properties_service_name,
boost::bind(&GazeboRosApiPlugin::setJointProperties,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
set_joint_properties_service_ = nh_->advertiseService(set_joint_properties_aso);
// Advertise more services on the custom queue
std::string set_link_state_service_name("set_link_state");
ros::AdvertiseServiceOptions set_link_state_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
set_link_state_service_name,
boost::bind(&GazeboRosApiPlugin::setLinkState,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
set_link_state_service_ = nh_->advertiseService(set_link_state_aso);
// Advertise topic on custom queue
// topic callback version for set_link_state
ros::SubscribeOptions link_state_so =
ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
"set_link_state",10,
boost::bind( &GazeboRosApiPlugin::updateLinkState,this,_1),
ros::VoidPtr(), &gazebo_queue_);
set_link_state_topic_ = nh_->subscribe(link_state_so);
// topic callback version for set_model_state
ros::SubscribeOptions model_state_so =
ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
"set_model_state",10,
boost::bind( &GazeboRosApiPlugin::updateModelState,this,_1),
ros::VoidPtr(), &gazebo_queue_);
set_model_state_topic_ = nh_->subscribe(model_state_so);
// Advertise more services on the custom queue
std::string pause_physics_service_name("pause_physics");
ros::AdvertiseServiceOptions pause_physics_aso =
ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
pause_physics_service_name,
boost::bind(&GazeboRosApiPlugin::pausePhysics,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
pause_physics_service_ = nh_->advertiseService(pause_physics_aso);
// Advertise more services on the custom queue
std::string unpause_physics_service_name("unpause_physics");
ros::AdvertiseServiceOptions unpause_physics_aso =
ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
unpause_physics_service_name,
boost::bind(&GazeboRosApiPlugin::unpausePhysics,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
unpause_physics_service_ = nh_->advertiseService(unpause_physics_aso);
// Advertise more services on the custom queue
std::string apply_body_wrench_service_name("apply_body_wrench");
ros::AdvertiseServiceOptions apply_body_wrench_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
apply_body_wrench_service_name,
boost::bind(&GazeboRosApiPlugin::applyBodyWrench,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
apply_body_wrench_service_ = nh_->advertiseService(apply_body_wrench_aso);
// Advertise more services on the custom queue
std::string apply_joint_effort_service_name("apply_joint_effort");
ros::AdvertiseServiceOptions apply_joint_effort_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
apply_joint_effort_service_name,
boost::bind(&GazeboRosApiPlugin::applyJointEffort,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
apply_joint_effort_service_ = nh_->advertiseService(apply_joint_effort_aso);
// Advertise more services on the custom queue
std::string clear_joint_forces_service_name("clear_joint_forces");
ros::AdvertiseServiceOptions clear_joint_forces_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
clear_joint_forces_service_name,
boost::bind(&GazeboRosApiPlugin::clearJointForces,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
clear_joint_forces_service_ = nh_->advertiseService(clear_joint_forces_aso);
// Advertise more services on the custom queue
std::string clear_body_wrenches_service_name("clear_body_wrenches");
ros::AdvertiseServiceOptions clear_body_wrenches_aso =
ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
clear_body_wrenches_service_name,
boost::bind(&GazeboRosApiPlugin::clearBodyWrenches,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
clear_body_wrenches_service_ = nh_->advertiseService(clear_body_wrenches_aso);
// Advertise more services on the custom queue
std::string reset_simulation_service_name("reset_simulation");
ros::AdvertiseServiceOptions reset_simulation_aso =
ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
reset_simulation_service_name,
boost::bind(&GazeboRosApiPlugin::resetSimulation,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
reset_simulation_service_ = nh_->advertiseService(reset_simulation_aso);
// Advertise more services on the custom queue
std::string reset_world_service_name("reset_world");
ros::AdvertiseServiceOptions reset_world_aso =
ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
reset_world_service_name,
boost::bind(&GazeboRosApiPlugin::resetWorld,this,_1,_2),
ros::VoidPtr(), &gazebo_queue_);
reset_world_service_ = nh_->advertiseService(reset_world_aso);
// set param for use_sim_time if not set by user already
nh_->setParam("/use_sim_time", true);
// todo: contemplate setting environment variable ROBOT=sim here???
nh_->getParam("pub_clock_frequency", pub_clock_frequency_);
last_pub_clock_time_ = world_->GetSimTime();
}
void GazeboRosApiPlugin::onLinkStatesConnect()
{
pub_link_states_connection_count_++;
if (pub_link_states_connection_count_ == 1) // connect on first subscriber
pub_link_states_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishLinkStates,this));
}
void GazeboRosApiPlugin::onModelStatesConnect()
{
pub_model_states_connection_count_++;
if (pub_model_states_connection_count_ == 1) // connect on first subscriber
pub_model_states_event_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosApiPlugin::publishModelStates,this));
}
void GazeboRosApiPlugin::onLinkStatesDisconnect()
{
pub_link_states_connection_count_--;
if (pub_link_states_connection_count_ <= 0) // disconnect with no subscribers
{
gazebo::event::Events::DisconnectWorldUpdateBegin(pub_link_states_event_);
if (pub_link_states_connection_count_ < 0) // should not be possible
ROS_ERROR("one too mandy disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
}
}
void GazeboRosApiPlugin::onModelStatesDisconnect()
{
pub_model_states_connection_count_--;
if (pub_model_states_connection_count_ <= 0) // disconnect with no subscribers
{
gazebo::event::Events::DisconnectWorldUpdateBegin(pub_model_states_event_);
if (pub_model_states_connection_count_ < 0) // should not be possible
ROS_ERROR("one too mandy disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
}
}
bool GazeboRosApiPlugin::spawnURDFModel(gazebo_msgs::SpawnModel::Request &req,
gazebo_msgs::SpawnModel::Response &res)
{
// get name space for the corresponding model plugins
robot_namespace_ = req.robot_namespace;
// incoming robot model string
std::string model_xml = req.model_xml;
if (!isURDF(model_xml))
{
ROS_ERROR("SpawnModel: Failure - model format is not URDF.");
res.success = false;
res.status_message = "SpawnModel: Failure - model format is not URDF.";
return false;
}
/// STRIP DECLARATION <? ... xml version="1.0" ... ?> from model_xml
/// @todo: does tinyxml have functionality for this?
/// @todo: should gazebo take care of the declaration?
{
std::string open_bracket("<?");
std::string close_bracket("?>");
size_t pos1 = model_xml.find(open_bracket,0);
size_t pos2 = model_xml.find(close_bracket,0);
if (pos1 != std::string::npos && pos2 != std::string::npos)
model_xml.replace(pos1,pos2-pos1+2,std::string(""));
}
// Now, replace package://xxx with the full path to the package
{
std::string package_prefix("package://");
size_t pos1 = model_xml.find(package_prefix,0);
while (pos1 != std::string::npos)
{
size_t pos2 = model_xml.find("/", pos1+10);
//ROS_DEBUG(" pos %d %d",(int)pos1, (int)pos2);
if (pos2 == std::string::npos || pos1 >= pos2)
{
ROS_ERROR("malformed package name?");
break;
}
std::string package_name = model_xml.substr(pos1+10,pos2-pos1-10);
//ROS_DEBUG("package name [%s]", package_name.c_str());
std::string package_path = ros::package::getPath(package_name);
if (package_path.empty())
{
ROS_FATAL("Package[%s] does not have a path",package_name.c_str());
res.success = false;
res.status_message = std::string("urdf reference package name does not exist: ")+package_name;
return false;
}
ROS_DEBUG_ONCE("Package name [%s] has path [%s]", package_name.c_str(), package_path.c_str());
model_xml.replace(pos1,(pos2-pos1),package_path);
pos1 = model_xml.find(package_prefix, pos1);
}
}
// ROS_DEBUG("Model XML\n\n%s\n\n ",model_xml.c_str());
req.model_xml = model_xml;
// Model is now considered convert to SDF
return spawnSDFModel(req,res);
}
// DEPRECATED IN HYDRO
bool GazeboRosApiPlugin::spawnGazeboModel(gazebo_msgs::SpawnModel::Request &req,
gazebo_msgs::SpawnModel::Response &res)
{
ROS_WARN_STREAM_NAMED("api_plugin","/gazebo/spawn_gazebo_model is deprecated, use /gazebo/spawn_sdf_model instead");
spawnSDFModel(req, res);
}
bool GazeboRosApiPlugin::spawnSDFModel(gazebo_msgs::SpawnModel::Request &req,
gazebo_msgs::SpawnModel::Response &res)
{
// incoming robot name
std::string model_name = req.model_name;
// get name space for the corresponding model plugins
robot_namespace_ = req.robot_namespace;
// get initial pose of model
gazebo::math::Vector3 initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
// get initial roll pitch yaw (fixed frame transform)
gazebo::math::Quaternion initial_q(req.initial_pose.orientation.w,req.initial_pose.orientation.x,req.initial_pose.orientation.y,req.initial_pose.orientation.z);
// refernce frame for initial pose definition, modify initial pose if defined
gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.reference_frame));
if (frame)
{
// convert to relative pose
gazebo::math::Pose frame_pose = frame->GetWorldPose();
initial_xyz = frame_pose.rot.RotateVector(initial_xyz);
initial_xyz += frame_pose.pos;
initial_q *= frame_pose.rot;
}
/// @todo: map is really wrong, need to use tf here somehow
else if (req.reference_frame == "" || req.reference_frame == "world" || req.reference_frame == "map" || req.reference_frame == "/map")
{
ROS_DEBUG("SpawnModel: reference_frame is empty/world/map, using inertial frame");
}
else
{
res.success = false;
res.status_message = "SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
return true;
}
// incoming robot model string
std::string model_xml = req.model_xml;
// store resulting Gazebo Model XML to be sent to spawn queue
// get incoming string containg either an URDF or a Gazebo Model XML
// grab from parameter server if necessary convert to SDF if necessary
stripXmlDeclaration(model_xml);
// put string in TiXmlDocument for manipulation
TiXmlDocument gazebo_model_xml;
gazebo_model_xml.Parse(model_xml.c_str());
// optional model manipulations: update initial pose && replace model name
if (isSDF(model_xml))
{
updateSDFAttributes(gazebo_model_xml, model_name, initial_xyz, initial_q);
// Walk recursively through the entire SDF, locate plugin tags and
// add robotNamespace as a child with the correct namespace
if (!this->robot_namespace_.empty())
{
// Get root element for SDF
TiXmlNode* model_tixml = gazebo_model_xml.FirstChild("sdf");
model_tixml = (!model_tixml) ?
gazebo_model_xml.FirstChild("gazebo") : model_tixml;
if (model_tixml)
{
walkChildAddRobotNamespace(model_tixml);
}
else
{
ROS_WARN("Unable to add robot namespace to xml");
}
}
}
else if (isURDF(model_xml))
{
updateURDFModelPose(gazebo_model_xml, initial_xyz, initial_q);
updateURDFName(gazebo_model_xml, model_name);
// Walk recursively through the entire URDF, locate plugin tags and
// add robotNamespace as a child with the correct namespace
if (!this->robot_namespace_.empty())
{
// Get root element for URDF
TiXmlNode* model_tixml = gazebo_model_xml.FirstChild("robot");
if (model_tixml)
{
walkChildAddRobotNamespace(model_tixml);
}
else
{
ROS_WARN("Unable to add robot namespace to xml");
}
}
}
else
{
ROS_ERROR("GazeboRosApiPlugin SpawnModel Failure: input xml format not recognized");
res.success = false;
res.status_message = std::string("GazeboRosApiPlugin SpawnModel Failure: input model_xml not SDF or URDF, or cannot be converted to Gazebo compatible format.");
return true;
}
// do spawning check if spawn worked, return response
return spawnAndConform(gazebo_model_xml, model_name, res);
}
bool GazeboRosApiPlugin::deleteModel(gazebo_msgs::DeleteModel::Request &req,
gazebo_msgs::DeleteModel::Response &res)
{
// clear forces, etc for the body in question
gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
if (!model)
{
ROS_ERROR("DeleteModel: model [%s] does not exist",req.model_name.c_str());
res.success = false;
res.status_message = "DeleteModel: model does not exist";
return true;
}
// delete wrench jobs on bodies
for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
{
gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
if (body)
{
// look for it in jobs, delete body wrench jobs
clearBodyWrenches(body->GetScopedName());
}
}
// delete force jobs on joints
gazebo::physics::Joint_V joints = model->GetJoints();
for (unsigned int i=0;i< joints.size(); i++)
{
// look for it in jobs, delete joint force jobs
clearJointForces(joints[i]->GetName());
}
// send delete model request
gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest("entity_delete",req.model_name);
request_pub_->Publish(*msg,true);
ros::Duration model_spawn_timeout(60.0);
ros::Time timeout = ros::Time::now() + model_spawn_timeout;
// wait and verify that model is deleted
while (true)
{
if (ros::Time::now() > timeout)
{
res.success = false;
res.status_message = std::string("DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation");
return true;
}
{
//boost::recursive_mutex::scoped_lock lock(*world->GetMRMutex());
if (!world_->GetModel(req.model_name)) break;
}
ROS_DEBUG("Waiting for model deletion (%s)",req.model_name.c_str());
usleep(1000);
}
// set result
res.success = true;
res.status_message = std::string("DeleteModel: successfully deleted model");
return true;
}
bool GazeboRosApiPlugin::getModelState(gazebo_msgs::GetModelState::Request &req,
gazebo_msgs::GetModelState::Response &res)
{
gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.relative_entity_name));
if (!model)
{
ROS_ERROR("GetModelState: model [%s] does not exist",req.model_name.c_str());
res.success = false;
res.status_message = "GetModelState: model does not exist";
return true;
}
else
{
/**
* @brief creates a header for the result
* @author Markus Bader markus.bader@tuwien.ac.at
* @date 21th Nov 2014
**/
{
std::map<std::string, unsigned int>::iterator it = access_count_get_model_state_.find(req.model_name);
if(it == access_count_get_model_state_.end())
{
access_count_get_model_state_.insert( std::pair<std::string, unsigned int>(req.model_name, 1) );
res.header.seq = 1;
}
else
{
it->second++;
res.header.seq = it->second;
}
res.header.stamp = ros::Time::now();
res.header.frame_id = req.relative_entity_name; /// @brief this is a redundant information
}
// get model pose
gazebo::math::Pose model_pose = model->GetWorldPose();
gazebo::math::Vector3 model_pos = model_pose.pos;
gazebo::math::Quaternion model_rot = model_pose.rot;
// get model twist
gazebo::math::Vector3 model_linear_vel = model->GetWorldLinearVel();
gazebo::math::Vector3 model_angular_vel = model->GetWorldAngularVel();
if (frame)
{
// convert to relative pose
gazebo::math::Pose frame_pose = frame->GetWorldPose();
model_pos = model_pos - frame_pose.pos;
model_pos = frame_pose.rot.RotateVectorReverse(model_pos);
model_rot *= frame_pose.rot.GetInverse();
// convert to relative rates
gazebo::math::Vector3 frame_vpos = frame->GetWorldLinearVel(); // get velocity in gazebo frame
gazebo::math::Vector3 frame_veul = frame->GetWorldAngularVel(); // get velocity in gazebo frame
model_linear_vel = frame_pose.rot.RotateVector(model_linear_vel - frame_vpos);
model_angular_vel = frame_pose.rot.RotateVector(model_angular_vel - frame_veul);
}
/// @todo: FIXME map is really wrong, need to use tf here somehow
else if (req.relative_entity_name == "" || req.relative_entity_name == "world" || req.relative_entity_name == "map" || req.relative_entity_name == "/map")
{
ROS_DEBUG("GetModelState: relative_entity_name is empty/world/map, using inertial frame");
}
else
{
res.success = false;
res.status_message = "GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
return true;
}
// fill in response
res.pose.position.x = model_pos.x;
res.pose.position.y = model_pos.y;
res.pose.position.z = model_pos.z;
res.pose.orientation.w = model_rot.w;
res.pose.orientation.x = model_rot.x;
res.pose.orientation.y = model_rot.y;
res.pose.orientation.z = model_rot.z;
res.twist.linear.x = model_linear_vel.x;
res.twist.linear.y = model_linear_vel.y;
res.twist.linear.z = model_linear_vel.z;
res.twist.angular.x = model_angular_vel.x;
res.twist.angular.y = model_angular_vel.y;
res.twist.angular.z = model_angular_vel.z;
res.success = true;
res.status_message = "GetModelState: got properties";
return true;
}
return true;
}
bool GazeboRosApiPlugin::getModelProperties(gazebo_msgs::GetModelProperties::Request &req,
gazebo_msgs::GetModelProperties::Response &res)
{
gazebo::physics::ModelPtr model = world_->GetModel(req.model_name);
if (!model)
{
ROS_ERROR("GetModelProperties: model [%s] does not exist",req.model_name.c_str());
res.success = false;
res.status_message = "GetModelProperties: model does not exist";
return true;
}
else
{
// get model parent name
gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
if (parent_model) res.parent_model_name = parent_model->GetName();
// get list of child bodies, geoms
res.body_names.clear();
res.geom_names.clear();
for (unsigned int i = 0 ; i < model->GetChildCount(); i ++)
{
gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
if (body)
{
res.body_names.push_back(body->GetName());
// get list of geoms
for (unsigned int j = 0; j < body->GetChildCount() ; j++)
{
gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
if (geom)
res.geom_names.push_back(geom->GetName());
}
}
}
// get list of joints
res.joint_names.clear();
gazebo::physics::Joint_V joints = model->GetJoints();
for (unsigned int i=0;i< joints.size(); i++)
res.joint_names.push_back( joints[i]->GetName() );
// get children model names
res.child_model_names.clear();
for (unsigned int j = 0; j < model->GetChildCount(); j++)
{
gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
if (child_model)
res.child_model_names.push_back(child_model->GetName() );
}
// is model static
res.is_static = model->IsStatic();
res.success = true;
res.status_message = "GetModelProperties: got properties";
return true;
}
return true;
}
bool GazeboRosApiPlugin::getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,
gazebo_msgs::GetWorldProperties::Response &res)
{
res.sim_time = world_->GetSimTime().Double();
res.model_names.clear();
for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
res.model_names.push_back(world_->GetModel(i)->GetName());
gzerr << "disablign rendering has not been implemented, rendering is always enabled\n";
res.rendering_enabled = true; //world->GetRenderEngineEnabled();
res.success = true;
res.status_message = "GetWorldProperties: got properties";
return true;
}
bool GazeboRosApiPlugin::getJointProperties(gazebo_msgs::GetJointProperties::Request &req,
gazebo_msgs::GetJointProperties::Response &res)
{
gazebo::physics::JointPtr joint;
for (unsigned int i = 0; i < world_->GetModelCount(); i ++)
{
joint = world_->GetModel(i)->GetJoint(req.joint_name);
if (joint) break;
}
if (!joint)
{
res.success = false;
res.status_message = "GetJointProperties: joint not found";
return true;
}
else
{
/// @todo: FIXME
res.type = res.REVOLUTE;
res.damping.clear(); // to be added to gazebo
//res.damping.push_back(joint->GetDamping(0));
res.position.clear(); // use GetAngle(i)
res.position.push_back(joint->GetAngle(0).Radian());
res.rate.clear(); // use GetVelocity(i)
res.rate.push_back(joint->GetVelocity(0));
res.success = true;
res.status_message = "GetJointProperties: got properties";
return true;
}
}
bool GazeboRosApiPlugin::getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,
gazebo_msgs::GetLinkProperties::Response &res)
{
gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(world_->GetEntity(req.link_name));
if (!body)
{
res.success = false;
res.status_message = "GetLinkProperties: link not found, did you forget to scope the link by model name?";
return true;
}
else
{
/// @todo: validate
res.gravity_mode = body->GetGravityMode();
res.mass = body->GetInertial()->GetMass();
gazebo::physics::InertialPtr inertia = body->GetInertial();
res.ixx = inertia->GetIXX();
res.iyy = inertia->GetIYY();
res.izz = inertia->GetIZZ();
res.ixy = inertia->GetIXY();
res.ixz = inertia->GetIXZ();
res.iyz = inertia->GetIYZ();
gazebo::math::Vector3 com = body->GetInertial()->GetCoG();
res.com.position.x = com.x;
res.com.position.y = com.y;
res.com.position.z = com.z;