-
Notifications
You must be signed in to change notification settings - Fork 276
/
UserCommands.cc
1260 lines (1098 loc) · 37.9 KB
/
UserCommands.cc
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 (C) 2019 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.
*
*/
#include "UserCommands.hh"
#include <google/protobuf/message.h>
#include <ignition/msgs/boolean.pb.h>
#include <ignition/msgs/entity_factory.pb.h>
#include <ignition/msgs/light.pb.h>
#include <ignition/msgs/pose.pb.h>
#include <ignition/msgs/physics.pb.h>
#include <string>
#include <utility>
#include <vector>
#include <ignition/msgs/Utility.hh>
#include <sdf/Physics.hh>
#include <sdf/Root.hh>
#include <sdf/Error.hh>
#include <sdf/Light.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/transport/Node.hh>
#include "ignition/common/Profiler.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/LightCmd.hh"
#include "ignition/gazebo/components/Link.hh"
#include "ignition/gazebo/components/Model.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/PoseCmd.hh"
#include "ignition/gazebo/components/PhysicsCmd.hh"
#include "ignition/gazebo/components/World.hh"
#include "ignition/gazebo/Conversions.hh"
#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/SdfEntityCreator.hh"
#include "ignition/gazebo/components/ContactSensorData.hh"
#include "ignition/gazebo/components/ContactSensor.hh"
#include "ignition/gazebo/components/Sensor.hh"
using namespace ignition;
using namespace gazebo;
using namespace systems;
namespace ignition
{
namespace gazebo
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
/// \brief This class is passed to every command and contains interfaces that
/// can be shared among all commands. For example, all create and remove
/// commands can use the `creator` object.
class UserCommandsInterface
{
/// \brief Pointer to entity component manager. We don't assume ownership.
public: EntityComponentManager *ecm{nullptr};
/// \brief Creator interface, shared among all commands that need it.
public: std::unique_ptr<SdfEntityCreator> creator{nullptr};
/// \brief World entity.
public: Entity worldEntity{kNullEntity};
/// \brief Check if there's a contact sensor connected to a collision
/// component
/// \param[in] _collision Collision entity to be checked
/// \return True if a contact sensor is connected to the collision entity,
/// false otherwise
public: bool HasContactSensor(const Entity _collision);
};
/// \brief All user commands should inherit from this class so they can be
/// undone / redone.
class UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Message containing user command.
/// \param[in] _iface Pointer to interfaces shared by all commands.
public: UserCommandBase(google::protobuf::Message *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
/// \brief Destructor.
public: virtual ~UserCommandBase();
/// \brief Execute the command. All subclasses must implement this
/// function and update entities and components so the command takes effect.
/// \return True if command was properly executed.
public: virtual bool Execute() = 0;
/// \brief Message containing command.
protected: google::protobuf::Message *msg{nullptr};
/// \brief Keep pointer to interfaces shared among commands.
protected: const std::shared_ptr<UserCommandsInterface> iface{nullptr};
};
/// \brief Command to spawn an entity into simulation.
class CreateCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Factory message.
/// \param[in] _iface Pointer to user commands interface.
public: CreateCommand(msgs::EntityFactory *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
};
/// \brief Command to remove an entity from simulation.
class RemoveCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Message identifying the entity to be removed.
/// \param[in] _iface Pointer to user commands interface.
public: RemoveCommand(msgs::Entity *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
};
/// \brief Command to modify a light entity from simulation.
class LightCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Message identifying the entity to be edited.
/// \param[in] _iface Pointer to user commands interface.
public: LightCommand(msgs::Light *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
/// \brief Light equality comparison function.
public: std::function<bool(const msgs::Light &, const msgs::Light &)>
lightEql { [](const msgs::Light &_a, const msgs::Light &_b)
{
return
_a.type() == _b.type() &&
_a.name() == _b.name() &&
math::equal(
_a.diffuse().a(), _b.diffuse().a(), 1e-6f) &&
math::equal(
_a.diffuse().r(), _b.diffuse().r(), 1e-6f) &&
math::equal(
_a.diffuse().g(), _b.diffuse().g(), 1e-6f) &&
math::equal(
_a.diffuse().b(), _b.diffuse().b(), 1e-6f) &&
math::equal(
_a.specular().a(), _b.specular().a(), 1e-6f) &&
math::equal(
_a.specular().r(), _b.specular().r(), 1e-6f) &&
math::equal(
_a.specular().g(), _b.specular().g(), 1e-6f) &&
math::equal(
_a.specular().b(), _b.specular().b(), 1e-6f) &&
math::equal(
_a.range(), _b.range(), 1e-6f) &&
math::equal(
_a.attenuation_linear(),
_b.attenuation_linear(),
1e-6f) &&
math::equal(
_a.attenuation_constant(),
_b.attenuation_constant(),
1e-6f) &&
math::equal(
_a.attenuation_quadratic(),
_b.attenuation_quadratic(),
1e-6f) &&
_a.cast_shadows() == _b.cast_shadows() &&
math::equal(
_a.intensity(),
_b.intensity(),
1e-6f) &&
math::equal(
_a.direction().x(), _b.direction().x(), 1e-6) &&
math::equal(
_a.direction().y(), _b.direction().y(), 1e-6) &&
math::equal(
_a.direction().z(), _b.direction().z(), 1e-6) &&
math::equal(
_a.spot_inner_angle(), _b.spot_inner_angle(), 1e-6f) &&
math::equal(
_a.spot_outer_angle(), _b.spot_outer_angle(), 1e-6f) &&
math::equal(_a.spot_falloff(), _b.spot_falloff(), 1e-6f);
}};
};
/// \brief Command to update an entity's pose transform.
class PoseCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg pose message.
/// \param[in] _iface Pointer to user commands interface.
public: PoseCommand(msgs::Pose *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
/// \brief Pose3d equality comparison function.
public: std::function<bool(const math::Pose3d &, const math::Pose3d &)>
pose3Eql { [](const math::Pose3d &_a, const math::Pose3d &_b)
{
return _a.Pos().Equal(_b.Pos(), 1e-6) &&
math::equal(_a.Rot().X(), _b.Rot().X(), 1e-6) &&
math::equal(_a.Rot().Y(), _b.Rot().Y(), 1e-6) &&
math::equal(_a.Rot().Z(), _b.Rot().Z(), 1e-6) &&
math::equal(_a.Rot().W(), _b.Rot().W(), 1e-6);
}};
};
/// \brief Command to modify the physics parameters of a simulation.
class PhysicsCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Message containing the new physics parameters.
/// \param[in] _iface Pointer to user commands interface.
public: PhysicsCommand(msgs::Physics *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
};
/// \brief Command to enable a collision component.
class EnableCollisionCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Message identifying the collision to be enabled.
/// \param[in] _iface Pointer to user commands interface.
public: EnableCollisionCommand(msgs::Entity *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
};
/// \brief Command to disable a collision component.
class DisableCollisionCommand : public UserCommandBase
{
/// \brief Constructor
/// \param[in] _msg Message identifying the collision to be disabled.
/// \param[in] _iface Pointer to user commands interface.
public: DisableCollisionCommand(msgs::Entity *_msg,
std::shared_ptr<UserCommandsInterface> &_iface);
// Documentation inherited
public: bool Execute() final;
};
}
}
}
}
/// \brief Private UserCommands data class.
class ignition::gazebo::systems::UserCommandsPrivate
{
/// \brief Callback for create service
/// \param[in] _req Request containing entity description.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the entity will be successfully spawned.
/// \return True if successful.
public: bool CreateService(const msgs::EntityFactory &_req,
msgs::Boolean &_res);
/// \brief Callback for multiple create service
/// \param[in] _req Request containing one or more entity descriptions.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the entities will be successfully spawned.
/// \return True if successful.
public: bool CreateServiceMultiple(
const msgs::EntityFactory_V &_req, msgs::Boolean &_res);
/// \brief Callback for remove service
/// \param[in] _req Request containing identification of entity to be removed.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the entity will be successfully removed.
/// \return True if successful.
public: bool RemoveService(const msgs::Entity &_req,
msgs::Boolean &_res);
/// \brief Callback for light service
/// \param[in] _req Request containing light update of an entity.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the light will be successfully updated.
/// \return True if successful.
public: bool LightService(const msgs::Light &_req, msgs::Boolean &_res);
/// \brief Callback for pose service
/// \param[in] _req Request containing pose update of an entity.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the entity will be successfully moved.
/// \return True if successful.
public: bool PoseService(const msgs::Pose &_req, msgs::Boolean &_res);
/// \brief Callback for physics service
/// \param[in] _req Request containing updates to the physics parameters.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the physics parameters will be successfully updated.
/// \return True if successful.
public: bool PhysicsService(const msgs::Physics &_req, msgs::Boolean &_res);
/// \brief Callback for enable collision service
/// \param[in] _req Request containing collision entity.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the collision will be successfully enabled.
/// \return True if successful.
public: bool EnableCollisionService(
const msgs::Entity &_req, msgs::Boolean &_res);
/// \brief Callback for disable collision service
/// \param[in] _req Request containing collision entity.
/// \param[in] _res True if message successfully received and queued.
/// It does not mean that the collision will be successfully disabled.
/// \return True if successful.
public: bool DisableCollisionService(
const msgs::Entity &_req, msgs::Boolean &_res);
/// \brief Queue of commands pending execution.
public: std::vector<std::unique_ptr<UserCommandBase>> pendingCmds;
/// \brief Ignition communication node.
public: transport::Node node;
/// \brief Object holding several interfaces that can be used by any command.
public: std::shared_ptr<UserCommandsInterface> iface{nullptr};
/// \brief Mutex to protect pending queue.
public: std::mutex pendingMutex;
};
//////////////////////////////////////////////////
UserCommands::UserCommands() : System(),
dataPtr(std::make_unique<UserCommandsPrivate>())
{
}
//////////////////////////////////////////////////
UserCommands::~UserCommands() = default;
//////////////////////////////////////////////////
bool UserCommandsInterface::HasContactSensor(const Entity _collision)
{
auto *linkEntity = ecm->Component<components::ParentEntity>(_collision);
auto allLinkSensors =
ecm->EntitiesByComponents(components::Sensor(),
components::ParentEntity(*linkEntity));
for (auto const &sensor : allLinkSensors)
{
// Check if it is a contact sensor
auto isContactSensor =
ecm->EntityHasComponentType(sensor, components::ContactSensor::typeId);
if (!isContactSensor)
continue;
// Check if sensor is connected to _collision
auto componentName = ecm->Component<components::Name>(_collision);
std::string collisionName = componentName->Data();
auto sensorSDF = ecm->Component<components::ContactSensor>(sensor)->Data();
auto sensorCollisionName =
sensorSDF->GetElement("contact")->Get<std::string>("collision");
if (collisionName == sensorCollisionName)
{
return true;
}
}
return false;
}
//////////////////////////////////////////////////
void UserCommands::Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &,
EntityComponentManager &_ecm,
EventManager &_eventManager)
{
// Create interfaces shared among commands
this->dataPtr->iface = std::make_shared<UserCommandsInterface>();
this->dataPtr->iface->worldEntity = _entity;
this->dataPtr->iface->ecm = &_ecm;
this->dataPtr->iface->creator =
std::make_unique<SdfEntityCreator>(_ecm, _eventManager);
const components::Name *constCmp = _ecm.Component<components::Name>(_entity);
const std::string &worldName = constCmp->Data();
auto validWorldName = transport::TopicUtils::AsValidTopic(worldName);
if (validWorldName.empty())
{
ignerr << "World name [" << worldName
<< "] doesn't work well with transport, services not advertised."
<< std::endl;
return;
}
// Create service
std::string createService{"/world/" + validWorldName + "/create"};
this->dataPtr->node.Advertise(createService,
&UserCommandsPrivate::CreateService, this->dataPtr.get());
// Create service for EntityFactory_V
std::string createServiceMultiple{"/world/" + validWorldName +
"/create_multiple"};
this->dataPtr->node.Advertise(createServiceMultiple,
&UserCommandsPrivate::CreateServiceMultiple, this->dataPtr.get());
ignmsg << "Create service on [" << createService << "]" << std::endl;
// Remove service
std::string removeService{"/world/" + validWorldName + "/remove"};
this->dataPtr->node.Advertise(removeService,
&UserCommandsPrivate::RemoveService, this->dataPtr.get());
ignmsg << "Remove service on [" << removeService << "]" << std::endl;
// Pose service
std::string poseService{"/world/" + validWorldName + "/set_pose"};
this->dataPtr->node.Advertise(poseService,
&UserCommandsPrivate::PoseService, this->dataPtr.get());
ignmsg << "Pose service on [" << poseService << "]" << std::endl;
// Light service
std::string lightService{"/world/" + validWorldName + "/light_config"};
this->dataPtr->node.Advertise(lightService,
&UserCommandsPrivate::LightService, this->dataPtr.get());
ignmsg << "Light configuration service on [" << lightService << "]"
<< std::endl;
// Physics service
std::string physicsService{"/world/" + validWorldName + "/set_physics"};
this->dataPtr->node.Advertise(physicsService,
&UserCommandsPrivate::PhysicsService, this->dataPtr.get());
ignmsg << "Physics service on [" << physicsService << "]" << std::endl;
// Enable collision service
std::string enableCollisionService{
"/world/" + validWorldName + "/enable_collision"};
this->dataPtr->node.Advertise(enableCollisionService,
&UserCommandsPrivate::EnableCollisionService, this->dataPtr.get());
ignmsg << "Enable collision service on [" << enableCollisionService << "]"
<< std::endl;
// Disable collision service
std::string disableCollisionService{
"/world/" + validWorldName + "/disable_collision"};
this->dataPtr->node.Advertise(disableCollisionService,
&UserCommandsPrivate::DisableCollisionService, this->dataPtr.get());
ignmsg << "Disable collision service on [" << disableCollisionService << "]"
<< std::endl;
}
//////////////////////////////////////////////////
void UserCommands::PreUpdate(const UpdateInfo &/*_info*/,
EntityComponentManager &)
{
IGN_PROFILE("UserCommands::PreUpdate");
// make a copy the cmds so execution does not block receiving other
// incoming cmds
std::vector<std::unique_ptr<UserCommandBase>> cmds;
{
std::lock_guard<std::mutex> lock(this->dataPtr->pendingMutex);
if (this->dataPtr->pendingCmds.empty())
return;
cmds = std::move(this->dataPtr->pendingCmds);
this->dataPtr->pendingCmds.clear();
}
// TODO(louise) Record current world state for undo
// Execute pending commands
for (auto &cmd : cmds)
{
// Execute
if (!cmd->Execute())
continue;
// TODO(louise) Update command with current world state
// TODO(louise) Move to undo list
}
// TODO(louise) Clear redo list
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::CreateServiceMultiple(
const msgs::EntityFactory_V &_req, msgs::Boolean &_res)
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
for (int i = 0; i < _req.data_size(); ++i)
{
const msgs::EntityFactory &msg = _req.data(i);
// Create command and push it to queue
auto msgCopy = msg.New();
msgCopy->CopyFrom(msg);
auto cmd = std::make_unique<CreateCommand>(msgCopy, this->iface);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::CreateService(const msgs::EntityFactory &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<CreateCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::RemoveService(const msgs::Entity &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<RemoveCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::LightService(const msgs::Light &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<LightCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::PoseService(const msgs::Pose &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<PoseCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::EnableCollisionService(const msgs::Entity &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<EnableCollisionCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::DisableCollisionService(const msgs::Entity &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<DisableCollisionCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
bool UserCommandsPrivate::PhysicsService(const msgs::Physics &_req,
msgs::Boolean &_res)
{
// Create command and push it to queue
auto msg = _req.New();
msg->CopyFrom(_req);
auto cmd = std::make_unique<PhysicsCommand>(msg, this->iface);
// Push to pending
{
std::lock_guard<std::mutex> lock(this->pendingMutex);
this->pendingCmds.push_back(std::move(cmd));
}
_res.set_data(true);
return true;
}
//////////////////////////////////////////////////
UserCommandBase::UserCommandBase(google::protobuf::Message *_msg,
std::shared_ptr<UserCommandsInterface> &_iface)
: msg(_msg), iface(_iface)
{
}
//////////////////////////////////////////////////
UserCommandBase::~UserCommandBase()
{
if (this->msg != nullptr)
delete this->msg;
this->msg = nullptr;
}
//////////////////////////////////////////////////
CreateCommand::CreateCommand(msgs::EntityFactory *_msg,
std::shared_ptr<UserCommandsInterface> &_iface)
: UserCommandBase(_msg, _iface)
{
}
//////////////////////////////////////////////////
bool CreateCommand::Execute()
{
auto createMsg = dynamic_cast<const msgs::EntityFactory *>(this->msg);
if (nullptr == createMsg)
{
ignerr << "Internal error, null create message" << std::endl;
return false;
}
// Load SDF
sdf::Root root;
sdf::Light lightSdf;
sdf::Errors errors;
switch (createMsg->from_case())
{
case msgs::EntityFactory::kSdf:
{
errors = root.LoadSdfString(createMsg->sdf());
break;
}
case msgs::EntityFactory::kSdfFilename:
{
errors = root.Load(createMsg->sdf_filename());
break;
}
case msgs::EntityFactory::kModel:
{
// TODO(louise) Support model msg
ignerr << "model field not yet supported." << std::endl;
return false;
}
case msgs::EntityFactory::kLight:
{
lightSdf = convert<sdf::Light>(createMsg->light());
break;
}
case msgs::EntityFactory::kCloneName:
{
auto entityToClone = this->iface->ecm->EntityByComponents(
components::Name(createMsg->clone_name()));
auto parentComp =
this->iface->ecm->Component<components::ParentEntity>(entityToClone);
auto parentEntity = parentComp ? parentComp->Data() : kNullEntity;
auto clonedEntity = this->iface->ecm->Clone(entityToClone, parentEntity,
createMsg->name(), createMsg->allow_renaming());
if (kNullEntity == clonedEntity)
{
ignerr << "Request to clone an entity named ["
<< createMsg->clone_name() << "] failed." << std::endl;
return false;
}
if (createMsg->has_pose())
{
// TODO(anyone) handle if relative_to is filled
auto pose = gazebo::convert<math::Pose3d>(createMsg->pose());
this->iface->ecm->SetComponentData<components::Pose>(clonedEntity,
pose);
}
return true;
}
default:
{
ignerr << "Missing [from] field in create message." << std::endl;
return false;
}
}
if (!errors.empty())
{
for (auto &err : errors)
ignerr << err << std::endl;
return false;
}
bool isModel{false};
bool isLight{false};
bool isActor{false};
bool isRoot{false};
if (nullptr != root.Model())
{
isRoot = true;
isModel = true;
}
else if (nullptr != root.Light())
{
isRoot = true;
isLight = true;
}
else if (nullptr != root.Actor())
{
isRoot = true;
isActor = true;
}
else if (!lightSdf.Name().empty())
{
isLight = true;
}
else
{
ignerr << "Expected exactly one top-level <model>, <light> or <actor> on"
<< " SDF." << std::endl;
return false;
}
if ((isModel && isLight) || (isModel && isActor) || (isLight && isActor))
{
ignwarn << "Expected exactly one top-level <model>, <light> or <actor>, "
<< "but found more. Only the 1st will be spawned." << std::endl;
}
// Check the name of the entity being spawned
std::string desiredName;
if (!createMsg->name().empty())
{
desiredName = createMsg->name();
}
else if (isModel)
{
desiredName = root.Model()->Name();
}
else if (isLight && isRoot)
{
desiredName = root.Light()->Name();
}
else if (isLight)
{
desiredName = lightSdf.Name();
}
else if (isActor)
{
desiredName = root.Actor()->Name();
}
// Check if there's already a top-level entity with the given name
if (kNullEntity != this->iface->ecm->EntityByComponents(
components::Name(desiredName),
components::ParentEntity(this->iface->worldEntity)))
{
if (!createMsg->allow_renaming())
{
ignwarn << "Entity named [" << desiredName << "] already exists and "
<< "[allow_renaming] is false. Entity not spawned."
<< std::endl;
return false;
}
// Generate unique name
std::string newName = desiredName;
int i = 0;
while (kNullEntity != this->iface->ecm->EntityByComponents(
components::Name(newName),
components::ParentEntity(this->iface->worldEntity)))
{
newName = desiredName + "_" + std::to_string(i++);
}
desiredName = newName;
}
// Create entities
Entity entity{kNullEntity};
if (isModel)
{
auto model = *root.Model();
model.SetName(desiredName);
entity = this->iface->creator->CreateEntities(&model);
}
else if (isLight && isRoot)
{
auto light = *root.Light();
light.SetName(desiredName);
entity = this->iface->creator->CreateEntities(&light);
}
else if (isLight)
{
lightSdf.SetName(desiredName);
entity = this->iface->creator->CreateEntities(&lightSdf);
}
else if (isActor)
{
auto actor = *root.Actor();
actor.SetName(desiredName);
entity = this->iface->creator->CreateEntities(&actor);
}
this->iface->creator->SetParent(entity, this->iface->worldEntity);
// Pose
if (createMsg->has_pose())
{
auto poseComp = this->iface->ecm->Component<components::Pose>(entity);
*poseComp = components::Pose(msgs::Convert(createMsg->pose()));
}
igndbg << "Created entity [" << entity << "] named [" << desiredName << "]"
<< std::endl;
return true;
}
//////////////////////////////////////////////////
RemoveCommand::RemoveCommand(msgs::Entity *_msg,
std::shared_ptr<UserCommandsInterface> &_iface)
: UserCommandBase(_msg, _iface)
{
}
//////////////////////////////////////////////////
bool RemoveCommand::Execute()
{
auto removeMsg = dynamic_cast<const msgs::Entity *>(this->msg);
if (nullptr == removeMsg)
{
ignerr << "Internal error, null remove message" << std::endl;
return false;
}
Entity entity{kNullEntity};
if (removeMsg->id() != kNullEntity)
{
entity = removeMsg->id();
}
else if (!removeMsg->name().empty() &&
removeMsg->type() != msgs::Entity::NONE)
{
if (removeMsg->type() == msgs::Entity::MODEL)
{
entity = this->iface->ecm->EntityByComponents(components::Model(),
components::Name(removeMsg->name()));
}
else if (removeMsg->type() == msgs::Entity::LIGHT)
{
entity = this->iface->ecm->EntityByComponents(
components::Name(removeMsg->name()));
auto lightComp = this->iface->ecm->Component<components::Light>(entity);
if (nullptr == lightComp)
entity = kNullEntity;
}
else
{
ignerr << "Deleting entities of type [" << removeMsg->type()
<< "] is not supported." << std::endl;
return false;
}
}
else
{
ignerr << "Remove command missing either entity's ID or name + type"
<< std::endl;
return false;
}
if (entity == kNullEntity)
{
ignerr << "Entity named [" << removeMsg->name() << "] of type ["
<< removeMsg->type() << "] not found, so not removed." << std::endl;
return false;
}
// Check that we support removing this entity
auto parent = this->iface->ecm->ParentEntity(entity);
if (nullptr == this->iface->ecm->Component<components::World>(parent))
{
ignerr << "Entity [" << entity
<< "] is not a direct child of the world, so it can't be removed."
<< std::endl;
return false;
}
if (nullptr == this->iface->ecm->Component<components::Model>(entity) &&
nullptr == this->iface->ecm->Component<components::Light>(entity))
{
ignerr << "Entity [" << entity
<< "] is not a model or a light, so it can't be removed."
<< std::endl;
return false;
}
igndbg << "Requesting removal of entity [" << entity << "]" << std::endl;
this->iface->creator->RequestRemoveEntity(entity);
return true;
}
//////////////////////////////////////////////////
LightCommand::LightCommand(msgs::Light *_msg,
std::shared_ptr<UserCommandsInterface> &_iface)
: UserCommandBase(_msg, _iface)
{
}
//////////////////////////////////////////////////
bool LightCommand::Execute()
{
auto lightMsg = dynamic_cast<const msgs::Light *>(this->msg);
if (nullptr == lightMsg)
{
ignerr << "Internal error, null light message" << std::endl;
return false;
}
Entity lightEntity{kNullEntity};
if (lightMsg->id() != kNullEntity)
{
lightEntity = lightMsg->id();
}
else if (!lightMsg->name().empty())
{
if (lightMsg->parent_id() != kNullEntity)
{