ElevatorPluginPrivate.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 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 #ifndef _GAZEBO_ELEVATOR_PLUGIN_PRIVATE_HH_
19 #define _GAZEBO_ELEVATOR_PLUGIN_PRIVATE_HH_
20 
21 #include <list>
22 #include <mutex>
23 #include <string>
24 
25 #include <sdf/sdf.hh>
26 
27 #include <gazebo/transport/Node.hh>
29 #include <gazebo/msgs/msgs.hh>
30 #include <gazebo/common/PID.hh>
31 #include <gazebo/common/Timer.hh>
32 
33 namespace gazebo
34 {
38  {
40  public: ElevatorPluginPrivate() = default;
41 
43  public: virtual ~ElevatorPluginPrivate();
44 
46  public: class DoorController
47  {
50  public: enum Target {
53 
56  };
57 
60  public: enum State {
63 
66  };
67 
71  public: DoorController(physics::JointPtr _doorJoint);
72 
74  public: virtual ~DoorController() = default;
75 
78  public: void SetTarget(
80 
84 
88 
90  public: void Reset();
91 
95  public: virtual bool Update(const common::UpdateInfo &_info);
96 
99 
101  public: State state;
102 
104  public: Target target;
105 
108 
111  };
112 
114  public: class LiftController
115  {
118  public: enum State {
121 
124  };
125 
130  public: LiftController(physics::JointPtr _liftJoint,
131  float _floorHeight);
132 
134  public: virtual ~LiftController() = default;
135 
138  public: void SetFloor(int _floor);
139 
142  public: int GetFloor() const;
143 
147 
149  public: void Reset();
150 
154  public: virtual bool Update(const common::UpdateInfo &_info);
155 
157  public: State state;
158 
160  public: int floor;
161 
163  public: float floorHeight;
164 
167 
170 
173  };
174 
176  public: class State
177  {
179  public: State() : started(false) {}
180 
182  public: virtual ~State() = default;
183 
185  public: std::string name;
186 
188  public: virtual void Start() {}
189 
191  public: virtual bool Update() {return true;}
192 
194  protected: bool started;
195  };
196 
198  public: class CloseState : public State
199  {
203 
204  // Documentation inherited
205  public: virtual void Start();
206 
207  // Documentation inherited
208  public: virtual bool Update();
209 
212  };
213 
215  public: class OpenState : public State
216  {
220 
221  // Documentation inherited
222  public: virtual void Start();
223 
224  // Documentation inherited
225  public: virtual bool Update();
226 
229  };
230 
232  public: class MoveState : public State
233  {
237  public: MoveState(int _floor, LiftController *_ctrl);
238 
239  // Documentation inherited
240  public: virtual void Start();
241 
242  // Documentation inherited
243  public: virtual bool Update();
244 
246  public: int floor;
247 
250  };
251 
253  public: class WaitState : public State
254  {
257  public: WaitState(const common::Time &_waitTime);
258 
259  // Documentation inherited
260  public: virtual void Start();
261 
262  // Documentation inherited
263  public: virtual bool Update();
264 
267  };
268 
271 
274 
277 
279  public: sdf::ElementPtr sdf;
280 
283 
286 
290 
293 
296 
298  public: std::list<State *> states;
299 
301  public: std::mutex stateMutex;
302 
305  };
306 }
307 #endif
transport::NodePtr node
Node for communication.
Definition: ElevatorPluginPrivate.hh:285
sdf::ElementPtr sdf
SDF pointer.
Definition: ElevatorPluginPrivate.hh:279
int floor
Target floor number.
Definition: ElevatorPluginPrivate.hh:246
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:147
MoveState(int _floor, LiftController *_ctrl)
Constructor.
virtual bool Update(const common::UpdateInfo &_info)
Update the controller.
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
Controller for opening and closing the elevator door.
Definition: ElevatorPluginPrivate.hh:46
The door is moving.
Definition: ElevatorPluginPrivate.hh:62
State base class.
Definition: ElevatorPluginPrivate.hh:176
CloseState(ElevatorPluginPrivate::DoorController *_ctrl)
Constructor.
void SetFloor(int _floor)
Set the current floor to move to.
virtual void Start()
Used to start a state.
virtual bool Update()
Used to update a state.
Definition: ElevatorPluginPrivate.hh:191
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
physics::JointPtr liftJoint
Joint to control.
Definition: ElevatorPluginPrivate.hh:166
physics::JointPtr doorJoint
Pointer to the joint that opens the door.
Definition: ElevatorPluginPrivate.hh:276
State used to make the elevator wait.
Definition: ElevatorPluginPrivate.hh:253
bool started
True when started.
Definition: ElevatorPluginPrivate.hh:194
virtual ~State()=default
Destructor.
virtual bool Update()
Used to update a state.
physics::ModelPtr model
Pointer to the elevator model.
Definition: ElevatorPluginPrivate.hh:270
std::list< State * > states
List of states that should be executed.
Definition: ElevatorPluginPrivate.hh:298
virtual ~LiftController()=default
Destructor.
common::Time prevSimTime
Previous simulation time.
Definition: ElevatorPluginPrivate.hh:172
common::Time doorWaitTime
Time to hold the door in the open state.
Definition: ElevatorPluginPrivate.hh:304
Close the door.
Definition: ElevatorPluginPrivate.hh:55
DoorController(physics::JointPtr _doorJoint)
Constructor.
virtual void Start()
Used to start a state.
virtual ~ElevatorPluginPrivate()
Destructor.
Open the door.
Definition: ElevatorPluginPrivate.hh:52
ElevatorPluginPrivate::DoorController * ctrl
Pointer to the door controller.
Definition: ElevatorPluginPrivate.hh:228
Information for use in an update event.
Definition: UpdateInfo.hh:30
State()
Constructor.
Definition: ElevatorPluginPrivate.hh:179
common::Timer waitTimer
Timer to hold the door open.
Definition: ElevatorPluginPrivate.hh:266
State
Door motion states.
Definition: ElevatorPluginPrivate.hh:60
common::PID liftPID
PID controller.
Definition: ElevatorPluginPrivate.hh:169
DoorController * doorController
Door controller.
Definition: ElevatorPluginPrivate.hh:292
State
Lift state.
Definition: ElevatorPluginPrivate.hh:118
ElevatorPluginPrivate::DoorController::Target GetTarget() const
Get the current target.
virtual bool Update()
Used to update a state.
ElevatorPluginPrivate()=default
Constructor.
std::string name
State name.
Definition: ElevatorPluginPrivate.hh:185
ElevatorPluginPrivate::LiftController::State GetState() const
Get the current state.
virtual void Start()
Used to start a state.
Definition: ElevatorPluginPrivate.hh:188
State used to move the elevator to a floor.
Definition: ElevatorPluginPrivate.hh:232
The lift is moving.
Definition: ElevatorPluginPrivate.hh:120
State state
State of the controller.
Definition: ElevatorPluginPrivate.hh:157
virtual ~DoorController()=default
Destructor.
Target
Door targets.
Definition: ElevatorPluginPrivate.hh:50
float floorHeight
Height of each floor.
Definition: ElevatorPluginPrivate.hh:163
WaitState(const common::Time &_waitTime)
Constructor.
The lift is stationary.
Definition: ElevatorPluginPrivate.hh:123
ElevatorPluginPrivate::DoorController::State GetState() const
Get the current state.
LiftController * ctrl
Lift controller.
Definition: ElevatorPluginPrivate.hh:249
State used to open the elevator door.
Definition: ElevatorPluginPrivate.hh:215
A timer class, used to time things in real world walltime.
Definition: Timer.hh:38
common::PID doorPID
PID controller for the door.
Definition: ElevatorPluginPrivate.hh:107
The door is stationary.
Definition: ElevatorPluginPrivate.hh:65
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
Controller for raising and lowering the elevator.
Definition: ElevatorPluginPrivate.hh:114
event::ConnectionPtr updateConnection
Pointer to the update event connection.
Definition: ElevatorPluginPrivate.hh:282
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
int GetFloor() const
Get the current floor.
void SetTarget(ElevatorPluginPrivate::DoorController::Target _target)
Set the target for the door (OPEN or CLOSE).
Target target
Current door target.
Definition: ElevatorPluginPrivate.hh:104
virtual bool Update()
Used to update a state.
virtual bool Update(const common::UpdateInfo &_info)
Update the controller.
int floor
Floor the elevator is on or moving to.
Definition: ElevatorPluginPrivate.hh:160
common::Time prevSimTime
Previous simulation time.
Definition: ElevatorPluginPrivate.hh:110
std::mutex stateMutex
Mutex to protect states.
Definition: ElevatorPluginPrivate.hh:301
virtual void Start()
Used to start a state.
LiftController * liftController
Lift controller.
Definition: ElevatorPluginPrivate.hh:295
State used to close the elevator door.
Definition: ElevatorPluginPrivate.hh:198
virtual bool Update()
Used to update a state.
virtual void Start()
Used to start a state.
Definition: ElevatorPluginPrivate.hh:37
OpenState(ElevatorPluginPrivate::DoorController *_ctrl)
Constructor.
ElevatorPluginPrivate::DoorController * ctrl
Pointer to the door controller.
Definition: ElevatorPluginPrivate.hh:211
State state
Current door state.
Definition: ElevatorPluginPrivate.hh:101
Generic PID controller class.
Definition: PID.hh:36
transport::SubscriberPtr elevatorSub
Used to subscribe to command message.
Definition: ElevatorPluginPrivate.hh:289
physics::JointPtr liftJoint
Pointer to the joint that lifts the elevator.
Definition: ElevatorPluginPrivate.hh:273
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:39
physics::JointPtr doorJoint
Pointer to the door joint.
Definition: ElevatorPluginPrivate.hh:98
LiftController(physics::JointPtr _liftJoint, float _floorHeight)
Constructor.