18 #ifndef _GAZEBO_ELEVATOR_PLUGIN_PRIVATE_HH_
19 #define _GAZEBO_ELEVATOR_PLUGIN_PRIVATE_HH_
149 public:
void Reset();
182 public:
virtual ~State() =
default;
191 public:
virtual bool Update() {
return true;}
205 public:
virtual void Start();
208 public:
virtual bool Update();
222 public:
virtual void Start();
225 public:
virtual bool Update();
240 public:
virtual void Start();
243 public:
virtual bool Update();
260 public:
virtual void Start();
263 public:
virtual bool Update();
279 public: sdf::ElementPtr
sdf;
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.
void Reset()
Reset the controller.
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.
void Reset()
Reset the controller.
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.