-
Notifications
You must be signed in to change notification settings - Fork 251
/
UserCommands.hh
105 lines (98 loc) · 3.19 KB
/
UserCommands.hh
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
/*
* 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.
*
*/
#ifndef GZ_SIM_SYSTEMS_USERCOMMANDS_HH_
#define GZ_SIM_SYSTEMS_USERCOMMANDS_HH_
#include <memory>
#include <gz/sim/config.hh>
#include <gz/sim/System.hh>
namespace gz
{
namespace sim
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE {
namespace systems
{
// Forward declarations.
class UserCommandsPrivate;
/// \brief This system provides a Gazebo Transport interface to execute
/// commands while simulation is running.
///
/// \todo(louise) In the future, an interface undo/redo commands will also
/// be provided.
///
/// ### Spawn entity
///
/// * **Service**: `/world/<world name>/create`
/// * **Request type**: gz.msgs.EntityFactory
/// * **Response type**: gz.msgs.Boolean
///
/// ### Spawn multiple entities
///
/// This service can spawn multiple entities in the same iteration,
/// thereby eliminating simulation steps between entity spawn times.
///
/// * **Service**: `/world/<world name>/create_multiple`
/// * **Request type**: gz.msgs.EntityFactory_V
/// * **Response type**: gz.msgs.Boolean
///
/// ### Set entity pose
///
/// This service set the pose of entities
///
/// * **Service**: `/world/<world name>/set_pose`
/// * **Request type**: gz.msgs.Pose
/// * **Response type**: gz.msgs.Boolean
///
/// ### Set multiple entity poses
///
/// This service set the pose of multiple entities
///
/// * **Service**: `/world/<world name>/set_pose_vector`
/// * **Request type**: gz.msgs.Pose_V
/// * **Response type**: gz.msgs.Boolean
///
/// Try some examples described in examples/worlds/empty.sdf
class UserCommands final:
public System,
public ISystemConfigure,
public ISystemPreUpdate
{
/// \brief Constructor
public: explicit UserCommands();
/// \brief Destructor
public: ~UserCommands() final;
// Documentation inherited
public: void Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &_eventMgr) override;
/// \brief All received commands are queued in order of reception and
/// executed in order during PreUpdate.
/// \param[in] _info Contains information about the current simulation
/// iteration.
/// \param[in] _ecm The entity component manager.
public: void PreUpdate(const UpdateInfo &_info,
EntityComponentManager &_ecm) final;
/// \brief Private data pointer.
private: std::unique_ptr<UserCommandsPrivate> dataPtr;
};
}
}
}
}
#endif