The GazeboTaskboardSlot1 class represents a controller for taskboard model (slot1). More...
#include <GazeboTaskboard.h>
Classes | |
struct | Led |
The Led structrure describes the LED in the simulator and holds current led state. More... | |
struct | ManipulationState |
Holds entire manipulation state and used to manipulate taskboard programatically. More... | |
struct | TaskboardLeds |
This structure holds all led instances. More... | |
struct | TaskboardSlot1State |
This structure holds state of the main taskboard elements. More... | |
Public Member Functions | |
GazeboTaskboardSlot1 () | |
Plugin's default constructor. | |
virtual void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Initializes plugin by providing associated model. | |
~GazeboTaskboardSlot1 () | |
Plugin's destructor. | |
Private Types | |
enum | ThreeWayToggleSwitchState { eThreeWayState_Center, eThreeWayState_Down, eThreeWayState_Up } |
Switch state with 3 stable positions. More... | |
enum | TwoWayToggleSwitchState { eTwoWayState_Down, eTwoWayState_Up } |
Switch state with 2 stable positions. More... | |
Private Member Functions | |
math::Vector3 | computeEmpiricalTorque (double deviationAngle, double initialValue, double snapCoeff, double snapExp, double torqueCoeff) const |
Calculates empirical torque vector used to simulate switches/toggles rotation. | |
void | DeriveStateFromModel () |
Derives current state from the model's positional configuration. | |
double | GetTime () const |
Gets current simulation time in seconds. | |
void | HandleManipulation () |
Handles current manipulation state. | |
bool | InitJoints () |
Initializes all joints that are used by the plugin. | |
bool | InitLinks () |
Initializes all links that are used by the plugin. | |
bool | ManipulateNumPad (gazebo_taskboard::ManipulateNumPad::Request &request, gazebo_taskboard::ManipulateNumPad::Response &response) |
Peforms numpad buttons manipulation. | |
bool | ManipulatePowerCover (gazebo_taskboard::ManipulatePowerCover::Request &request, gazebo_taskboard::ManipulatePowerCover::Response &response) |
Peforms power cover manipulation. | |
bool | ManipulatePowerSwitch (gazebo_taskboard::ManipulatePowerSwitch::Request &request, gazebo_taskboard::ManipulatePowerSwitch::Response &response) |
Peforms power switch manipulation. | |
bool | ManipulateRockerSwitch (gazebo_taskboard::ManipulateRockerSwitch::Request &request, gazebo_taskboard::ManipulateRockerSwitch::Response &response) |
Peforms rocker switch manipulation. | |
bool | ManipulateSafeToggle (gazebo_taskboard::ManipulateSafeToggle::Request &request, gazebo_taskboard::ManipulateSafeToggle::Response &response) |
Peforms safe toggle (A03/A04/A05) manipulation. | |
void | MonitorNumpadStateChanges () |
Handles numpad buttons state changes. | |
void | MonitorPowerCoverStateChanges () |
Handles power cover state changes. | |
void | MonitorPowerSwitchStateChanges () |
Handles power switch state changes. | |
void | MonitorRockerSwitchA01StateChanges () |
Handles rocker switch A01 state changes. | |
void | MonitorSafeTogglesStateChanges () |
Handles safe toggles (A03/A04/A05) state changes. | |
void | OnUpdate () |
Simulates expected behavior according to the current state. | |
void | PublishState () |
Sends TaskboardPanelA message to /taskboard/TaskboardPanelA topic. | |
void | SetLedState (Led &led, bool on) |
Turns on/off the given LED. | |
void | TurnOffAllLeds () |
Turns off all LEDs. | |
void | TurnOnLeds () |
Turns on all LEDs that should be on in the current state. | |
bool | UpdateTransitionFromOutState2Way (physics::LinkPtr link, physics::JointPtr joint, TwoWayToggleSwitchState &state) const |
Makes joint transition from current OUT position to nearest UP/DOWN state. | |
bool | UpdateTransitionFromOutState3Way (physics::LinkPtr link, physics::JointPtr joint, ThreeWayToggleSwitchState &state) const |
Makes joint transition from current OUT position to nearest UP/CENTER/DOWN state. | |
Private Attributes | |
bool | firstFrameInitializationDone |
first frame update flag. | |
boost::scoped_ptr< TaskboardLeds > | leds |
the LEDs | |
bool | ledsReady |
indicates if the leds setup is done | |
physics::LinkPtr | linkA01Switch |
rocker switch link | |
physics::LinkPtr | linkPowerCover |
power cover link | |
physics::LinkPtr | linkPowerSwitch |
power switch link | |
physics::LinkPtr | linksBaseSafeToggle [SAFE_TOGGLES_COUNT] |
parent links for safe toggles | |
physics::LinkPtr | linksNumPad [NUM_PAD_BUTTONS_COUNT] |
the numpad buttons links | |
physics::LinkPtr | linksSafeToggle [SAFE_TOGGLES_COUNT] |
safe toggles links (A03/A04/A05) | |
boost::scoped_ptr < ManipulationState > | manipulationState |
Holds entire manipulation state. | |
physics::ModelPtr | model |
the model associated with this plugin | |
ros::NodeHandle | node |
the handle of plugin node | |
ros::Publisher | publisher |
publishers for sending messages about state changes | |
physics::JointPtr | safeTogglesRevoluteJoints [SAFE_TOGGLES_COUNT] |
safe toggles revolute joints | |
ros::ServiceServer | srv_manipulateNumPad |
service for numpad buttons manipulation | |
ros::ServiceServer | srv_manipulatePowerCover |
service for power cover manipulation | |
ros::ServiceServer | srv_manipulatePowerSwitch |
service for power switch manipulation | |
ros::ServiceServer | srv_manipulateRockerSwitch |
service for rocker switch manipulation | |
ros::ServiceServer | srv_manipulateSafeToggle |
service for safe toggles manipulation | |
boost::scoped_ptr < TaskboardSlot1State > | state |
Taskboard Slot1 state. | |
event::ConnectionPtr | updateConnection |
pointer to the update event connection | |
Static Private Attributes | |
static const int | NUM_PAD_BUTTONS_COUNT = 9 |
the numpad buttons count constant | |
static const int | SAFE_TOGGLES_COUNT = 3 |
the toggles count constant |
The GazeboTaskboardSlot1 class represents a controller for taskboard model (slot1).
It is implemented as gazebo ModelPlugin, the instane of this class is associated with taskboard model by the ROS gazebo plugin. The controller is responsible for simulating taskboard behavior in reaction to external influences in similar way as it happens for real ISS taskboard.
Definition at line 41 of file GazeboTaskboard.h.
enum gazebo::GazeboTaskboardSlot1::ThreeWayToggleSwitchState [private] |
Switch state with 3 stable positions.
Definition at line 60 of file GazeboTaskboard.h.
enum gazebo::GazeboTaskboardSlot1::TwoWayToggleSwitchState [private] |
Switch state with 2 stable positions.
Definition at line 54 of file GazeboTaskboard.h.
Plugin's default constructor.
Definition at line 309 of file GazeboTaskboard.cpp.
Plugin's destructor.
Plugin's desctructor.
Stops listening to the world update event.
Definition at line 320 of file GazeboTaskboard.cpp.
math::Vector3 GazeboTaskboardSlot1::computeEmpiricalTorque | ( | double | deviationAngle, |
double | initialValue, | ||
double | snapCoeff, | ||
double | snapExp, | ||
double | torqueCoeff | ||
) | const [private] |
Calculates empirical torque vector used to simulate switches/toggles rotation.
deviationAngle | the angle value counted from some central direction |
initialValue | specifies the initial amount of torque (this will be scaled by torqueCoeff) |
snapCoeff | scales the mantissa value |
snapExp | the exponent in the empirical expression |
torqueCoeff | the coefficient used to scale the entire torque vector |
Definition at line 1398 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::DeriveStateFromModel | ( | ) | [private] |
Derives current state from the model's positional configuration.
The state is derived only for elements that have more then one stable position. For elements that have only single stable position (like rocker switch) state is not derived from the model but directly initialized to single stable position.
Definition at line 500 of file GazeboTaskboard.cpp.
double GazeboTaskboardSlot1::GetTime | ( | ) | const [private] |
Gets current simulation time in seconds.
Definition at line 1416 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::HandleManipulation | ( | ) | [private] |
Handles current manipulation state.
Definition at line 1284 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::InitJoints | ( | ) | [private] |
Initializes all joints that are used by the plugin.
Definition at line 469 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::InitLinks | ( | ) | [private] |
Initializes all links that are used by the plugin.
Definition at line 405 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [virtual] |
Initializes plugin by providing associated model.
_parent | the models associated with this plugin instance |
_sdf | the SDF definition that holds models parameters |
Definition at line 335 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::ManipulateNumPad | ( | gazebo_taskboard::ManipulateNumPad::Request & | request, |
gazebo_taskboard::ManipulateNumPad::Response & | response | ||
) | [private] |
Peforms numpad buttons manipulation.
Applies the given amount of force to the given button.
request | the request object with manipulation parameters |
response | the response object |
Definition at line 1220 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::ManipulatePowerCover | ( | gazebo_taskboard::ManipulatePowerCover::Request & | request, |
gazebo_taskboard::ManipulatePowerCover::Response & | response | ||
) | [private] |
Peforms power cover manipulation.
Rotates the cover on the given angle.
request | the request object with manipulation parameters |
response | the response object |
Definition at line 1143 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::ManipulatePowerSwitch | ( | gazebo_taskboard::ManipulatePowerSwitch::Request & | request, |
gazebo_taskboard::ManipulatePowerSwitch::Response & | response | ||
) | [private] |
Peforms power switch manipulation.
Rotates the switch on the given angle.
request | the request object with manipulation parameters |
response | the response object |
Definition at line 1169 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::ManipulateRockerSwitch | ( | gazebo_taskboard::ManipulateRockerSwitch::Request & | request, |
gazebo_taskboard::ManipulateRockerSwitch::Response & | response | ||
) | [private] |
Peforms rocker switch manipulation.
Applies the given amount of torque to the rocker switch.
request | the request object with manipulation parameters |
response | the response object |
Definition at line 1195 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::ManipulateSafeToggle | ( | gazebo_taskboard::ManipulateSafeToggle::Request & | request, |
gazebo_taskboard::ManipulateSafeToggle::Response & | response | ||
) | [private] |
Peforms safe toggle (A03/A04/A05) manipulation.
Applies the given amount of force to the given toggle or rotates the toggle on the given angle.
request | the request object with manipulation parameters |
response | the response object |
Definition at line 1248 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::MonitorNumpadStateChanges | ( | ) | [private] |
Handles numpad buttons state changes.
Definition at line 723 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::MonitorPowerCoverStateChanges | ( | ) | [private] |
Handles power cover state changes.
Definition at line 583 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::MonitorPowerSwitchStateChanges | ( | ) | [private] |
Handles power switch state changes.
Definition at line 621 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::MonitorRockerSwitchA01StateChanges | ( | ) | [private] |
Handles rocker switch A01 state changes.
Definition at line 665 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::MonitorSafeTogglesStateChanges | ( | ) | [private] |
Handles safe toggles (A03/A04/A05) state changes.
Definition at line 860 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::OnUpdate | ( | ) | [private] |
Simulates expected behavior according to the current state.
The method is called regularly by Gazebo which allows the plugin to function as an active object.
Definition at line 546 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::PublishState | ( | ) | [private] |
Sends TaskboardPanelA message to /taskboard/TaskboardPanelA topic.
The message is initialized with controller's current state.
Definition at line 963 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::SetLedState | ( | Led & | led, |
bool | on | ||
) | [private] |
Turns on/off the given LED.
led | the Led instance |
on | true to turn on the LED, false to turn off the LED |
Definition at line 1037 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::TurnOffAllLeds | ( | ) | [private] |
Turns off all LEDs.
Definition at line 1114 of file GazeboTaskboard.cpp.
void GazeboTaskboardSlot1::TurnOnLeds | ( | ) | [private] |
Turns on all LEDs that should be on in the current state.
Definition at line 1073 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::UpdateTransitionFromOutState2Way | ( | physics::LinkPtr | link, |
physics::JointPtr | joint, | ||
TwoWayToggleSwitchState & | state | ||
) | const [private] |
Makes joint transition from current OUT position to nearest UP/DOWN state.
link | the link that is in transition state |
joint | the revolute joint of the link |
state | if the method detects that transition is over then final state is returned via this reference |
Definition at line 763 of file GazeboTaskboard.cpp.
bool GazeboTaskboardSlot1::UpdateTransitionFromOutState3Way | ( | physics::LinkPtr | link, |
physics::JointPtr | joint, | ||
ThreeWayToggleSwitchState & | state | ||
) | const [private] |
Makes joint transition from current OUT position to nearest UP/CENTER/DOWN state.
link | the link that is in transition state |
joint | the revolute joint of the link |
state | if the method detects that transition is over then final state is returned via this reference |
Definition at line 807 of file GazeboTaskboard.cpp.
bool gazebo::GazeboTaskboardSlot1::firstFrameInitializationDone [private] |
first frame update flag.
In Load method the physics engine is not ready for usage, for example, we can not create model at that point. On the first update frame the physics is ready and we can create all the necessary models (LEDs in our case).
Definition at line 141 of file GazeboTaskboard.h.
boost::scoped_ptr<TaskboardLeds> gazebo::GazeboTaskboardSlot1::leds [private] |
the LEDs
Definition at line 159 of file GazeboTaskboard.h.
bool gazebo::GazeboTaskboardSlot1::ledsReady [private] |
indicates if the leds setup is done
Definition at line 144 of file GazeboTaskboard.h.
physics::LinkPtr gazebo::GazeboTaskboardSlot1::linkA01Switch [private] |
rocker switch link
Definition at line 169 of file GazeboTaskboard.h.
physics::LinkPtr gazebo::GazeboTaskboardSlot1::linkPowerCover [private] |
power cover link
Definition at line 165 of file GazeboTaskboard.h.
physics::LinkPtr gazebo::GazeboTaskboardSlot1::linkPowerSwitch [private] |
power switch link
Definition at line 167 of file GazeboTaskboard.h.
physics::LinkPtr gazebo::GazeboTaskboardSlot1::linksBaseSafeToggle[SAFE_TOGGLES_COUNT] [private] |
parent links for safe toggles
Definition at line 174 of file GazeboTaskboard.h.
physics::LinkPtr gazebo::GazeboTaskboardSlot1::linksNumPad[NUM_PAD_BUTTONS_COUNT] [private] |
the numpad buttons links
Definition at line 183 of file GazeboTaskboard.h.
physics::LinkPtr gazebo::GazeboTaskboardSlot1::linksSafeToggle[SAFE_TOGGLES_COUNT] [private] |
safe toggles links (A03/A04/A05)
Definition at line 176 of file GazeboTaskboard.h.
boost::scoped_ptr<ManipulationState> gazebo::GazeboTaskboardSlot1::manipulationState [private] |
Holds entire manipulation state.
Definition at line 200 of file GazeboTaskboard.h.
physics::ModelPtr gazebo::GazeboTaskboardSlot1::model [private] |
the model associated with this plugin
Definition at line 150 of file GazeboTaskboard.h.
the handle of plugin node
Definition at line 147 of file GazeboTaskboard.h.
const int gazebo::GazeboTaskboardSlot1::NUM_PAD_BUTTONS_COUNT = 9 [static, private] |
the numpad buttons count constant
Definition at line 181 of file GazeboTaskboard.h.
publishers for sending messages about state changes
Definition at line 186 of file GazeboTaskboard.h.
const int gazebo::GazeboTaskboardSlot1::SAFE_TOGGLES_COUNT = 3 [static, private] |
the toggles count constant
Definition at line 172 of file GazeboTaskboard.h.
physics::JointPtr gazebo::GazeboTaskboardSlot1::safeTogglesRevoluteJoints[SAFE_TOGGLES_COUNT] [private] |
safe toggles revolute joints
Definition at line 178 of file GazeboTaskboard.h.
service for numpad buttons manipulation
Definition at line 196 of file GazeboTaskboard.h.
service for power cover manipulation
Definition at line 190 of file GazeboTaskboard.h.
service for power switch manipulation
Definition at line 192 of file GazeboTaskboard.h.
service for rocker switch manipulation
Definition at line 194 of file GazeboTaskboard.h.
service for safe toggles manipulation
Definition at line 198 of file GazeboTaskboard.h.
boost::scoped_ptr<TaskboardSlot1State> gazebo::GazeboTaskboardSlot1::state [private] |
Taskboard Slot1 state.
Definition at line 155 of file GazeboTaskboard.h.
pointer to the update event connection
Definition at line 153 of file GazeboTaskboard.h.