Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes
gazebo::GazeboTaskboardSlot1 Class Reference

The GazeboTaskboardSlot1 class represents a controller for taskboard model (slot1). More...

#include <ISSTaskboardPanelA.h>

List of all members.

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 (iss_taskboard_gazebo::ManipulateNumPad::Request &request, iss_taskboard_gazebo::ManipulateNumPad::Response &response)
 Peforms numpad buttons manipulation.
bool ManipulatePowerCover (iss_taskboard_gazebo::ManipulatePowerCover::Request &request, iss_taskboard_gazebo::ManipulatePowerCover::Response &response)
 Peforms power cover manipulation.
bool ManipulatePowerSwitch (iss_taskboard_gazebo::ManipulatePowerSwitch::Request &request, iss_taskboard_gazebo::ManipulatePowerSwitch::Response &response)
 Peforms power switch manipulation.
bool ManipulateRockerSwitch (iss_taskboard_gazebo::ManipulateRockerSwitch::Request &request, iss_taskboard_gazebo::ManipulateRockerSwitch::Response &response)
 Peforms rocker switch manipulation.
bool ManipulateSafeToggle (iss_taskboard_gazebo::ManipulateSafeToggle::Request &request, iss_taskboard_gazebo::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< TaskboardLedsleds
 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

Detailed Description

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.

Author:
KennyAlive
Version:
1.0

Definition at line 40 of file ISSTaskboardPanelA.h.


Member Enumeration Documentation

Switch state with 3 stable positions.

Enumerator:
eThreeWayState_Center 
eThreeWayState_Down 
eThreeWayState_Up 

Definition at line 59 of file ISSTaskboardPanelA.h.

Switch state with 2 stable positions.

Enumerator:
eTwoWayState_Down 
eTwoWayState_Up 

Definition at line 53 of file ISSTaskboardPanelA.h.


Constructor & Destructor Documentation

Plugin's default constructor.

Definition at line 310 of file ISSTaskboardPanelA.cpp.

Plugin's destructor.

Plugin's desctructor.

Stops listening to the world update event.

Definition at line 321 of file ISSTaskboardPanelA.cpp.


Member Function Documentation

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.

Parameters:
deviationAnglethe angle value counted from some central direction
initialValuespecifies the initial amount of torque (this will be scaled by torqueCoeff)
snapCoeffscales the mantissa value
snapExpthe exponent in the empirical expression
torqueCoeffthe coefficient used to scale the entire torque vector
Returns:
the computed torque vector

Definition at line 1399 of file ISSTaskboardPanelA.cpp.

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 501 of file ISSTaskboardPanelA.cpp.

double GazeboTaskboardSlot1::GetTime ( ) const [private]

Gets current simulation time in seconds.

Returns:
current simulation time in seconds

Definition at line 1417 of file ISSTaskboardPanelA.cpp.

Handles current manipulation state.

Definition at line 1285 of file ISSTaskboardPanelA.cpp.

Initializes all joints that are used by the plugin.

Returns:
true if the joints are initialized successfully, otherwise false

Definition at line 470 of file ISSTaskboardPanelA.cpp.

bool GazeboTaskboardSlot1::InitLinks ( ) [private]

Initializes all links that are used by the plugin.

Returns:
true if the links are initialized successfully, otherwise false

Definition at line 406 of file ISSTaskboardPanelA.cpp.

void GazeboTaskboardSlot1::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
) [virtual]

Initializes plugin by providing associated model.

Parameters:
_parentthe models associated with this plugin instance
_sdfthe SDF definition that holds models parameters

Definition at line 336 of file ISSTaskboardPanelA.cpp.

bool GazeboTaskboardSlot1::ManipulateNumPad ( iss_taskboard_gazebo::ManipulateNumPad::Request &  request,
iss_taskboard_gazebo::ManipulateNumPad::Response &  response 
) [private]

Peforms numpad buttons manipulation.

Applies the given amount of force to the given button.

Parameters:
requestthe request object with manipulation parameters
responsethe response object
Returns:
true if the operation succeeded, otherwise false

Definition at line 1221 of file ISSTaskboardPanelA.cpp.

bool GazeboTaskboardSlot1::ManipulatePowerCover ( iss_taskboard_gazebo::ManipulatePowerCover::Request &  request,
iss_taskboard_gazebo::ManipulatePowerCover::Response &  response 
) [private]

Peforms power cover manipulation.

Rotates the cover on the given angle.

Parameters:
requestthe request object with manipulation parameters
responsethe response object
Returns:
true if the operation succeeded, otherwise false

Definition at line 1144 of file ISSTaskboardPanelA.cpp.

bool GazeboTaskboardSlot1::ManipulatePowerSwitch ( iss_taskboard_gazebo::ManipulatePowerSwitch::Request &  request,
iss_taskboard_gazebo::ManipulatePowerSwitch::Response &  response 
) [private]

Peforms power switch manipulation.

Rotates the switch on the given angle.

Parameters:
requestthe request object with manipulation parameters
responsethe response object
Returns:
true if the operation succeeded, otherwise false

Definition at line 1170 of file ISSTaskboardPanelA.cpp.

bool GazeboTaskboardSlot1::ManipulateRockerSwitch ( iss_taskboard_gazebo::ManipulateRockerSwitch::Request &  request,
iss_taskboard_gazebo::ManipulateRockerSwitch::Response &  response 
) [private]

Peforms rocker switch manipulation.

Applies the given amount of torque to the rocker switch.

Parameters:
requestthe request object with manipulation parameters
responsethe response object
Returns:
true if the operation succeeded, otherwise false

Definition at line 1196 of file ISSTaskboardPanelA.cpp.

bool GazeboTaskboardSlot1::ManipulateSafeToggle ( iss_taskboard_gazebo::ManipulateSafeToggle::Request &  request,
iss_taskboard_gazebo::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.

Parameters:
requestthe request object with manipulation parameters
responsethe response object
Returns:
true if the operation succeeded, otherwise false

Definition at line 1249 of file ISSTaskboardPanelA.cpp.

Handles numpad buttons state changes.

Definition at line 724 of file ISSTaskboardPanelA.cpp.

Handles power cover state changes.

Definition at line 584 of file ISSTaskboardPanelA.cpp.

Handles power switch state changes.

Definition at line 622 of file ISSTaskboardPanelA.cpp.

Handles rocker switch A01 state changes.

Definition at line 666 of file ISSTaskboardPanelA.cpp.

Handles safe toggles (A03/A04/A05) state changes.

Definition at line 861 of file ISSTaskboardPanelA.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 547 of file ISSTaskboardPanelA.cpp.

Sends TaskboardPanelA message to /taskboard/TaskboardPanelA topic.

The message is initialized with controller's current state.

Definition at line 964 of file ISSTaskboardPanelA.cpp.

void GazeboTaskboardSlot1::SetLedState ( Led led,
bool  on 
) [private]

Turns on/off the given LED.

Parameters:
ledthe Led instance
ontrue to turn on the LED, false to turn off the LED

Definition at line 1038 of file ISSTaskboardPanelA.cpp.

Turns off all LEDs.

Definition at line 1115 of file ISSTaskboardPanelA.cpp.

Turns on all LEDs that should be on in the current state.

Definition at line 1074 of file ISSTaskboardPanelA.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.

Parameters:
linkthe link that is in transition state
jointthe revolute joint of the link
stateif the method detects that transition is over then final state is returned via this reference
Returns:
true if the transition is over, otherwise false

Definition at line 764 of file ISSTaskboardPanelA.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.

Parameters:
linkthe link that is in transition state
jointthe revolute joint of the link
stateif the method detects that transition is over then final state is returned via this reference
Returns:
true if the transition is over, otherwise false

Definition at line 808 of file ISSTaskboardPanelA.cpp.


Member Data Documentation

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 140 of file ISSTaskboardPanelA.h.

boost::scoped_ptr<TaskboardLeds> gazebo::GazeboTaskboardSlot1::leds [private]

the LEDs

Definition at line 158 of file ISSTaskboardPanelA.h.

indicates if the leds setup is done

Definition at line 143 of file ISSTaskboardPanelA.h.

physics::LinkPtr gazebo::GazeboTaskboardSlot1::linkA01Switch [private]

rocker switch link

Definition at line 168 of file ISSTaskboardPanelA.h.

power cover link

Definition at line 164 of file ISSTaskboardPanelA.h.

power switch link

Definition at line 166 of file ISSTaskboardPanelA.h.

parent links for safe toggles

Definition at line 173 of file ISSTaskboardPanelA.h.

the numpad buttons links

Definition at line 182 of file ISSTaskboardPanelA.h.

safe toggles links (A03/A04/A05)

Definition at line 175 of file ISSTaskboardPanelA.h.

Holds entire manipulation state.

Definition at line 199 of file ISSTaskboardPanelA.h.

physics::ModelPtr gazebo::GazeboTaskboardSlot1::model [private]

the model associated with this plugin

Definition at line 149 of file ISSTaskboardPanelA.h.

the handle of plugin node

Definition at line 146 of file ISSTaskboardPanelA.h.

const int gazebo::GazeboTaskboardSlot1::NUM_PAD_BUTTONS_COUNT = 9 [static, private]

the numpad buttons count constant

Definition at line 180 of file ISSTaskboardPanelA.h.

publishers for sending messages about state changes

Definition at line 185 of file ISSTaskboardPanelA.h.

const int gazebo::GazeboTaskboardSlot1::SAFE_TOGGLES_COUNT = 3 [static, private]

the toggles count constant

Definition at line 171 of file ISSTaskboardPanelA.h.

safe toggles revolute joints

Definition at line 177 of file ISSTaskboardPanelA.h.

service for numpad buttons manipulation

Definition at line 195 of file ISSTaskboardPanelA.h.

service for power cover manipulation

Definition at line 189 of file ISSTaskboardPanelA.h.

service for power switch manipulation

Definition at line 191 of file ISSTaskboardPanelA.h.

service for rocker switch manipulation

Definition at line 193 of file ISSTaskboardPanelA.h.

service for safe toggles manipulation

Definition at line 197 of file ISSTaskboardPanelA.h.

Taskboard Slot1 state.

Definition at line 154 of file ISSTaskboardPanelA.h.

pointer to the update event connection

Definition at line 152 of file ISSTaskboardPanelA.h.


The documentation for this class was generated from the following files:


iss_taskboard_gazebo
Author(s):
autogenerated on Sat Jun 8 2019 19:20:28