Classes |
class | MantisInfo::MantisCapabilities |
| provides polymorphic robot capability detection/mapping More...
|
Namespaces |
namespace | MantisInfo |
| Contains information about a Mantis robot, such as number of joints, LEDs, etc.
|
Variables |
const char *const | MantisInfo::TargetName = "Mantis" |
| the name of the model, to be used for logging and remote GUIs
|
const unsigned int | MantisInfo::FrameTime = 32 |
| time between frames in the motion system (milliseconds)
|
const unsigned int | MantisInfo::NumFrames = 1 |
| the number of frames per buffer (don't forget also double buffered)
|
const unsigned int | MantisInfo::SoundBufferTime = 32 |
| the number of milliseconds per sound buffer... I'm not sure if this can be changed
|
const fmat::Column< 3 > | MantisInfo::AgentBoundingBoxBaseFrameOffset = fmat::pack(400,70,350) |
| Offset needed so that the centroid of the robot is correct related to the bounding box.
|
const fmat::Column< 3 > | MantisInfo::AgentBoundingBoxHalfDims = fmat::pack(100,100,100) |
| Half of the length, width, and height of the robot.
|
|
|
const unsigned | MantisInfo::NumWheels = 0 |
| The number of joints per front leg.
|
const unsigned | MantisInfo::FingerJointsPerArm = 0 |
| The number of joints per front leg.
|
const unsigned | MantisInfo::JointsPerArm = 0 |
| The number of joints per front leg.
|
const unsigned | MantisInfo::NumArms = 0 |
| The number of joints per front leg.
|
const unsigned | MantisInfo::NumArmJoints = JointsPerArm*NumArms |
| The number of joints per front leg.
|
const unsigned | MantisInfo::JointsPerFrLeg = 7 |
| The number of joints per front leg.
|
const unsigned | MantisInfo::JointsPerPosLeg = 4 |
| The number of joints per posterior leg (middle and the back legs).
|
const unsigned | MantisInfo::NumFrLegs = 2 |
| The number of front legs.
|
const unsigned | MantisInfo::NumGrippers = NumFrLegs |
| The number of grippers.
|
const unsigned | MantisInfo::NumPosLegs = 4 |
| The number of posterior legs.
|
const unsigned | MantisInfo::NumLegs = NumFrLegs + NumPosLegs |
| The number of legs.
|
const unsigned | MantisInfo::NumFrLegJoints = JointsPerFrLeg*NumFrLegs |
| the TOTAL number of joints in FRONT legs
|
const unsigned | MantisInfo::NumPosLegJoints = JointsPerPosLeg*NumPosLegs |
| the TOTAL number of joints in POSTERIOR legs
|
const unsigned | MantisInfo::NumLegJoints = NumFrLegJoints + NumPosLegJoints |
| the TOTAL number of joints on ALL legs
|
const unsigned | MantisInfo::NumHeadJoints = 3 |
| The number of joints in the pantiltroll.
|
const unsigned | MantisInfo::NumTailJoints = 0 |
| The number of joints assigned to the tail.
|
const unsigned | MantisInfo::NumMouthJoints = 0 |
| the number of joints that control the mouth
|
const unsigned | MantisInfo::NumEarJoints = 0 |
| The number of joints which control the ears (NOT per ear, is total).
|
const unsigned | MantisInfo::NumButtons = 3 |
| the number of buttons that are available
|
const unsigned | MantisInfo::NumSensors = 11 |
| the number of sensors available
|
const unsigned | MantisInfo::NumFacePanelLEDs = 0 |
| The number of face panel LEDs.
|
const unsigned | MantisInfo::NumPIDJoints = NumArmJoints + 1 + NumLegJoints + NumHeadJoints + NumTailJoints + NumMouthJoints |
| servo pins (also includes the thorax joint)
|
const unsigned | MantisInfo::NumLEDs = NumPIDJoints |
| There's an LED on every dynamixel, but can't see most of them, so save some computational resources and only expose the visible ones.
|
const unsigned | MantisInfo::NumOutputs = NumWheels + NumPIDJoints + NumLEDs |
| the total number of outputs
|
const unsigned | MantisInfo::NumReferenceFrames = NumOutputs + NumLegs + NumArms + NumGrippers + 1 + 1 |
| for the feet, grippers, base and camera
|
const float | MantisInfo::BallOfFootRadius = 0 |
| radius of the ball of the foot
|
const unsigned | MantisInfo::FrontLegExtra = JointsPerFrLeg -1 |
| The number of extra joints in front legs.
|
Input Offsets |
The order in which inputs should be stored
|
#define | RAD(deg) (((deg) * (float)M_PI ) / 180.0f) |
| Just a little macro for converting degrees to radians.
|
#define | __RI_RAD_FLAG |
| a flag so we undef these after we're done - do you have a cleaner solution?
|
enum | MantisInfo::ButtonOffset_t { MantisInfo::GreenButOffset,
MantisInfo::RedButOffset,
MantisInfo::YellowButOffset
} |
| holds offsets to different buttons in WorldState::buttons[]
More...
|
enum | MantisInfo::SensorOffset_t {
MantisInfo::LeftIRDistOffset,
MantisInfo::CenterIRDistOffset,
MantisInfo::IRDistOffset = CenterIRDistOffset,
MantisInfo::RightIRDistOffset,
MantisInfo::LeftLuminosityOffset,
MantisInfo::CenterLuminosityOffset,
MantisInfo::RightLuminosityOffset,
MantisInfo::MicVolumeOffset,
MantisInfo::MicSpikeCountOffset,
MantisInfo::PowerRemainOffset,
MantisInfo::PowerThermoOffset,
MantisInfo::PowerVoltageOffset
} |
| holds offset to different sensor values in WorldState::sensors[]
More...
|
enum | MantisInfo::ServoParam_t { MantisInfo::DYNAMIXEL_SLOPE = 0,
MantisInfo::DYNAMIXEL_PUNCH,
MantisInfo::DYNAMIXEL_MARGIN
} |
| offsets into DefaultPIDs, since Dynamixel servos don't actually use PID control, but a different set of parameters
More...
|
const char *const | MantisInfo::buttonNames [NumButtons+1] = { "GreenBut", "RedBut", "YellowBut", NULL } |
| Provides a string name for each button.
|
const char *const | MantisInfo::sensorNames [NumSensors+1] |
| Provides a string name for each sensor.
|
const char *const | MantisInfo::outputNames [NumReferenceFrames+1] |
| Names for each of the outputs.
|
const MantisCapabilities | MantisInfo::capabilities |
| allocation declared in RobotInfo.cc
|
const float | MantisInfo::DefaultPIDs [NumPIDJoints][3] |
| Dynamixel servos don't use PID control. Instead, these values indicate compliance slope (P), punch (add to P*error), compliance margin (min error to start applying torque) (see ServoParam_t).
|
const float | MantisInfo::MaxOutputSpeed [NumOutputs] |
| These values are our recommended maximum joint velocities, in rad/ms.
|
const float | MantisInfo::outputRanges [NumOutputs][2] |
| This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange).
|
const float | MantisInfo::mechanicalLimits [NumOutputs][2] |
| This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange).
|
Output Offsets |
Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file
|
enum | MantisInfo::LegOrder_t {
MantisInfo::LFrLegOrder = 0,
MantisInfo::RFrLegOrder,
MantisInfo::LMdLegOrder,
MantisInfo::RMdLegOrder,
MantisInfo::LBkLegOrder,
MantisInfo::RBkLegOrder
} |
| the ordering of legs
More...
|
enum | MantisInfo::FrLegOffset_t {
MantisInfo::FrSweepOffset = 0,
MantisInfo::FrElevatorOffset,
MantisInfo::FrTwist1Offset,
MantisInfo::FrElbowOffset,
MantisInfo::FrTwist2Offset,
MantisInfo::FrWristOffset,
MantisInfo::FrGripperOffset
} |
| The offsets within the Front Legs. Note that the ordering matches the actual physical ordering of joints on the appendage.
More...
|
enum | MantisInfo::PosLegOffset_t { MantisInfo::PosSweepOffset = 0,
MantisInfo::PosRotorOffset,
MantisInfo::PosElevatorOffset,
MantisInfo::PosKneeOffset
} |
| The offsets within the Posterior Legs. Note that the ordering matches the actual physical ordering of joints on the appendage.
More...
|
enum | MantisInfo::TPROffset_t { MantisInfo::PanOffset = 0,
MantisInfo::TiltOffset,
MantisInfo::RollOffset
} |
| The offsets of appendages with tilt (elevation), pan (heading), and roll or nod joints (i.e. head/wrist).
More...
|
enum | MantisInfo::LegOffset_t {
MantisInfo::LFrLegOffset = LegOffset+LFrLegOrder*JointsPerFrLeg,
MantisInfo::RFrLegOffset = LegOffset+RFrLegOrder*JointsPerFrLeg,
MantisInfo::LMdLegOffset = LegOffset+LMdLegOrder*JointsPerPosLeg + FrontLegExtra,
MantisInfo::RMdLegOffset = LegOffset+RMdLegOrder*JointsPerPosLeg + FrontLegExtra,
MantisInfo::LBkLegOffset = LegOffset+LBkLegOrder*JointsPerPosLeg + FrontLegExtra,
MantisInfo::RBkLegOffset = LegOffset+RBkLegOrder*JointsPerPosLeg + FrontLegExtra
} |
| The offsets of the individual legs, add REKOffset_t value to access specific joint.
More...
|
enum | MantisInfo::HeadOffset_t { MantisInfo::HeadPanOffset = HeadOffset,
MantisInfo::HeadTiltOffset,
MantisInfo::HeadRollOffset
} |
| These are 'absolute' offsets for the neck joints, don't need to add to HeadOffset like TPROffset_t values do.
More...
|
enum | MantisInfo::LEDOffset_t { MantisInfo::PowerRedLEDOffset = LEDOffset,
MantisInfo::PowerGreenLEDOffset,
MantisInfo::PlayLEDOffset,
MantisInfo::AdvanceLEDOffset
} |
| The offsets of the individual LEDs.
More...
|
typedef unsigned int | MantisInfo::LEDBitMask_t |
| So you can be clear when you're refering to a LED bitmask.
|
const unsigned | MantisInfo::PIDJointOffset = 0 |
| The beginning of the PID Joints.
|
const unsigned | MantisInfo::LegOffset = PIDJointOffset |
| the offset of the beginning of the regular leg joints (after the 1 rotator joint for the right front leg): NumLegs of JointsPerLeg each, in LegOrder_t order; see LegOffset_t
|
const unsigned | MantisInfo::ThoraxJointOffset = LegOffset+NumLegJoints |
| the offset of the beginning of the head joints, add TPROffset_t to get specific joint
|
const unsigned | MantisInfo::HeadOffset = ThoraxJointOffset + 1 |
| the ordering of legs
|
const unsigned | MantisInfo::LEDOffset = PIDJointOffset + NumPIDJoints |
| the offset of LEDs in WorldState::outputs and MotionCommand functions, see LedOffset_t for specific offsets
|
const unsigned | MantisInfo::BaseFrameOffset = NumOutputs |
| Use with kinematics to refer to base reference frame.
|
const unsigned | MantisInfo::FootFrameOffset = BaseFrameOffset + 1 |
| Use with kinematics to refer to feet reference frames (add appropriate LegOrder_t to specify which paw).
|
const unsigned | MantisInfo::GripperFrameOffset = FootFrameOffset+NumLegs |
| Use with kinematics to refer to gripper reference frame.
|
const unsigned | MantisInfo::CameraFrameOffset = GripperFrameOffset + NumGrippers |
| Use with kinematics to refer to camera reference frame.
|
const LEDOffset_t | MantisInfo::RedLEDOffset = PowerRedLEDOffset |
| the ordering of legs
|
const LEDOffset_t | MantisInfo::BlueLEDOffset = AdvanceLEDOffset |
| the ordering of legs
|
const LEDOffset_t | MantisInfo::GreenLEDOffset = PlayLEDOffset |
| the ordering of legs
|
const LEDOffset_t | MantisInfo::YellowLEDOffset = AdvanceLEDOffset |
| the ordering of legs
|
const LEDBitMask_t | MantisInfo::BlueLEDMask = (1<<(AdvanceLEDOffset-LEDOffset)) | (1<<(PowerRedLEDOffset-LEDOffset)) |
| the ordering of legs
|
const LEDBitMask_t | MantisInfo::GreenLEDMask = 1<<(GreenLEDOffset-LEDOffset) |
| mask corresponding to GreenLEDOffset
|
const LEDBitMask_t | MantisInfo::YellowLEDMask = 1<<(YellowLEDOffset-LEDOffset) |
| mask corresponding to YellowLEDOffset
|
const LEDBitMask_t | MantisInfo::RedLEDMask = 1<<(RedLEDOffset-LEDOffset) |
| mask corresponding to RedLEDOffset
|
const LEDBitMask_t | MantisInfo::PowerRedLEDMask = 1<<(PowerRedLEDOffset-LEDOffset) |
| mask corresponding to BlueLEDOffset
|
const LEDBitMask_t | MantisInfo::PowerGreenLEDMask = 1<<(PowerGreenLEDOffset-LEDOffset) |
| mask corresponding to GreenLEDOffset
|
const LEDBitMask_t | MantisInfo::PlayLEDMask = 1<<(PlayLEDOffset-LEDOffset) |
| mask corresponding to YellowLEDOffset
|
const LEDBitMask_t | MantisInfo::AdvanceLEDMask = 1<<(AdvanceLEDOffset-LEDOffset) |
| mask corresponding to RedLEDOffset
|
const LEDBitMask_t | MantisInfo::FaceLEDMask = 0 |
| LEDs for the face panel (all FaceLEDPanelMask<<(0:NumFacePanelLEDs-1) entries).
|
const LEDBitMask_t | MantisInfo::AllLEDMask = (LEDBitMask_t)~0 |
| selects all of the leds
|
Defines some capabilities of the Mantis robots.