#include "../include/ISSTaskboardPanelA.h"#include <boost/bind.hpp>#include <boost/algorithm/string.hpp>#include <stdio.h>#include <math.h>#include <gazebo/common/Events.hh>#include <std_msgs/String.h>#include <gazebo/math/Angle.hh>#include <gazebo/math/Pose.hh>#include <gazebo/msgs/MessageTypes.hh>
Go to the source code of this file.
Classes | |
| struct | BaseManipulationState |
| Holds base manipulation parameters: startTime and duration. More... | |
| struct | gazebo::GazeboTaskboardSlot1::Led |
| The Led structrure describes the LED in the simulator and holds current led state. More... | |
| struct | gazebo::GazeboTaskboardSlot1::ManipulationState |
| Holds entire manipulation state and used to manipulate taskboard programatically. More... | |
| struct | NumPadButtonManipulationState |
| Holds manipulation state for numpad buttons. More... | |
| struct | PowerCoverManipulationState |
| Holds manipulation state for power cover. More... | |
| struct | PowerSwitchManipulationState |
| Holds manipulation state for power switch. More... | |
| struct | RockerSwitchManipulationState |
| Holds manipulation state for rocker switch. More... | |
| struct | SafeToggleManipulationState |
| Holds manipulation state for safe toggles (A03/A04/A05). More... | |
| struct | gazebo::GazeboTaskboardSlot1::TaskboardLeds |
| This structure holds all led instances. More... | |
| struct | gazebo::GazeboTaskboardSlot1::TaskboardSlot1State |
| This structure holds state of the main taskboard elements. More... | |
Enumerations | |
| enum | LedColor { eLedColor_Green, eLedColor_Blue } |
| The available LED colors. More... | |
Functions | |
| double | deg2rad (double degrees) |
| Converts degrees to radians. | |
| static physics::JointPtr | getJoint (physics::ModelPtr model, const std::string &jointName) |
| Gets the model's joint by the joint name. | |
| static physics::LinkPtr | getLink (physics::ModelPtr model, const std::string &linkName) |
| Gets the model's link by the link name. | |
Variables | |
| const double | LED_HIDE_OFFSET = 100.0 |
| z coordinate offset for hiding led model in ON state | |
| const double | LED_HIDE_OFFSET2 = 105.0 |
| the z coordinate offset for hiding led model in OFF state | |
| const std::string | LED_MATERIAL_BLUE = "Gazebo/BlueGlow" |
| the material for blue led | |
| const std::string | LED_MATERIAL_GREEN = "Gazebo/GreenGlow" |
| the material for green led | |
| const std::string | LED_MATERIAL_OFF = "Gazebo/Grey" |
| the material for led in OFF state | |
| const double | NUMPAD_LED_LENGTH = 0.0004 |
| led's model cylinder length used for numpad buttons | |
| const double | NUMPAD_LED_RADIUS = 0.0095 |
| led's model cylinder radius used for numpad buttons | |
| const double | POWER_COVER_JOINT_THRESHOLD = M_PI/4 |
| the middle position for power cover | |
| const double | SAFE_TOGGLE_HALF_ANGLE = 0.47 |
| half angle angle angle for A03/A04/A05 toggles | |
| const double | SAFE_TOGGLE_LOWER_LIMIT_ANGLE = -0.94 |
| lower limit for A03/A04/A05 toggles as defined in URDF | |
| const double | SAFE_TOGGLE_MIDDLE_LIMIT_ANGLE = -0.47 |
| middle position for A03/A04/A05 toggles | |
| const double | SAFE_TOGGLE_UPPER_LIMIT_ANGLE = 0.0 |
| upper limit for A03/A04/A05 toggles as defined in URDF | |
| const double | SIMPLE_LED_LENGTH = 0.0004 |
| led's model cylinder length used for toggles/switches | |
| const double | SIMPLE_LED_RADIUS = 0.003 |
| led's model cylinder radius used for toggles/switches | |
| const math::Vector3 | ZERO_VECTOR = math::Vector3(0, 0, 0) |
| Zero vector constant for convenience. | |
| enum LedColor |
The available LED colors.
Definition at line 63 of file ISSTaskboardPanelA.cpp.
| double deg2rad | ( | double | degrees | ) | [inline] |
Converts degrees to radians.
| degrees | the angle value in degrees |
Definition at line 301 of file ISSTaskboardPanelA.cpp.
| static physics::JointPtr getJoint | ( | physics::ModelPtr | model, |
| const std::string & | jointName | ||
| ) | [static] |
Gets the model's joint by the joint name.
The function also prints ROS fatal message if fails to get the joint.
| model | the model to get joint from |
| jointName | the joint name |
Definition at line 455 of file ISSTaskboardPanelA.cpp.
| static physics::LinkPtr getLink | ( | physics::ModelPtr | model, |
| const std::string & | linkName | ||
| ) | [static] |
Gets the model's link by the link name.
The function also prints ROS fatal message if fails to get the link.
| model | the model to get link from |
| linkName | the link name |
Definition at line 391 of file ISSTaskboardPanelA.cpp.
| const double LED_HIDE_OFFSET = 100.0 |
z coordinate offset for hiding led model in ON state
Definition at line 46 of file ISSTaskboardPanelA.cpp.
| const double LED_HIDE_OFFSET2 = 105.0 |
the z coordinate offset for hiding led model in OFF state
Definition at line 48 of file ISSTaskboardPanelA.cpp.
| const std::string LED_MATERIAL_BLUE = "Gazebo/BlueGlow" |
the material for blue led
Definition at line 34 of file ISSTaskboardPanelA.cpp.
| const std::string LED_MATERIAL_GREEN = "Gazebo/GreenGlow" |
the material for green led
Definition at line 32 of file ISSTaskboardPanelA.cpp.
| const std::string LED_MATERIAL_OFF = "Gazebo/Grey" |
the material for led in OFF state
Definition at line 30 of file ISSTaskboardPanelA.cpp.
| const double NUMPAD_LED_LENGTH = 0.0004 |
led's model cylinder length used for numpad buttons
Definition at line 41 of file ISSTaskboardPanelA.cpp.
| const double NUMPAD_LED_RADIUS = 0.0095 |
led's model cylinder radius used for numpad buttons
Definition at line 43 of file ISSTaskboardPanelA.cpp.
| const double POWER_COVER_JOINT_THRESHOLD = M_PI/4 |
the middle position for power cover
Definition at line 27 of file ISSTaskboardPanelA.cpp.
| const double SAFE_TOGGLE_HALF_ANGLE = 0.47 |
half angle angle angle for A03/A04/A05 toggles
Definition at line 57 of file ISSTaskboardPanelA.cpp.
| const double SAFE_TOGGLE_LOWER_LIMIT_ANGLE = -0.94 |
lower limit for A03/A04/A05 toggles as defined in URDF
Definition at line 53 of file ISSTaskboardPanelA.cpp.
| const double SAFE_TOGGLE_MIDDLE_LIMIT_ANGLE = -0.47 |
middle position for A03/A04/A05 toggles
Definition at line 55 of file ISSTaskboardPanelA.cpp.
| const double SAFE_TOGGLE_UPPER_LIMIT_ANGLE = 0.0 |
upper limit for A03/A04/A05 toggles as defined in URDF
Definition at line 51 of file ISSTaskboardPanelA.cpp.
| const double SIMPLE_LED_LENGTH = 0.0004 |
led's model cylinder length used for toggles/switches
Definition at line 37 of file ISSTaskboardPanelA.cpp.
| const double SIMPLE_LED_RADIUS = 0.003 |
led's model cylinder radius used for toggles/switches
Definition at line 39 of file ISSTaskboardPanelA.cpp.
| const math::Vector3 ZERO_VECTOR = math::Vector3(0, 0, 0) |
Zero vector constant for convenience.
Definition at line 60 of file ISSTaskboardPanelA.cpp.