#include <vector>#include <sstream>#include "youbot_driver/generic/Units.hpp"#include "youbot_driver/generic-joint/JointParameter.hpp"#include "youbot_driver/generic-gripper/GripperParameter.hpp"#include "youbot_driver/youbot/ProtocolDefinitions.hpp"#include "youbot_driver/youbot/YouBotSlaveMsg.hpp"#include "youbot_driver/youbot/YouBotSlaveMailboxMsg.hpp"

Go to the source code of this file.
Classes | |
| class | youbot::ActualAcceleration |
| The current acceleration (read only). More... | |
| class | youbot::ActualLoadValue |
| Readout of the actual load value with used for stall detection (stallGuard2). More... | |
| class | youbot::ActualPosition |
| Actual position of one gripper bar. More... | |
| class | youbot::ActualVelocity |
| Actual velocity of one gripper bar. More... | |
| class | youbot::BarSpacingOffset |
| Represents a bar spacing offset. It could be useful if the gripper can not be totally closed. More... | |
| class | youbot::CalibrateGripper |
| Calibrate the gripper. More... | |
| class | youbot::ChopperBlankTime |
| Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For low current drivers, a setting of 1 or 2 is good. More... | |
| class | youbot::ChopperHysteresisDecrement |
| class | youbot::ChopperHysteresisEnd |
| class | youbot::ChopperHysteresisStart |
| Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value. More... | |
| class | youbot::ChopperMode |
| class | youbot::ChopperOffTime |
| class | youbot::DoubleStepEnable |
| class | youbot::ErrorFlags |
| class | youbot::Freewheeling |
| class | youbot::GripperBarName |
| The name for a gripper bar or finger. More... | |
| class | youbot::GripperFirmwareVersion |
| the firmware version of the gripper More... | |
| class | youbot::MaxEncoderValue |
| The encoder value when the gripper has reached it's maximum bar spacing position. More... | |
| class | youbot::MaximumAcceleration |
| Acceleration parameter for velocity control and position control. More... | |
| class | youbot::MaximumCurrent |
| The most important motor setting, since too high values might cause motor damage! The maximum value is 255. This value means 100% of the maximum current of the module. The current adjustment is within the range 0... 255 and can be adjusted in 32 steps (0... 255 divided by eight; e.g. step 0 = 0... 7, step 1 = 8... 15 and so on). More... | |
| class | youbot::MaximumPositioningSpeed |
| The limit for acceleration (and deceleration). Changing this parameter requires re-calculation of the acceleration factor (no. 146) and the acceleration divisor (no. 137), which is done automatically. More... | |
| class | youbot::MaxTravelDistance |
| The maximum bar spacing distance of the gripper. More... | |
| class | youbot::MicrostepResolution |
| class | youbot::MinimumSpeed |
| Should always be set 1 to ensure exact reaching of the target position. Do not change! More... | |
| class | youbot::PositionSetpoint |
| Position setpoint for one gripper bar. More... | |
| class | youbot::PowerDownDelay |
| Standstill period before the current is changed down to standby current. The standard value is 200 (value equates 2000msec). More... | |
| class | youbot::PulseDivisor |
| The exponent of the scaling factor for the pulse (step) generator should be de/incremented carefully (in steps of one). More... | |
| class | youbot::RampDivisor |
| The exponent of the scaling factor for the ramp generator- should be de/incremented carefully (in steps of one). More... | |
| class | youbot::RampMode |
| class | youbot::ShortDetectionTimer |
| class | youbot::ShortProtectionDisable |
| class | youbot::SlopeControlHighSide |
| class | youbot::SlopeControlLowSide |
| Determines the slope of the motor driver outputs. Set identical to slope control high side. More... | |
| class | youbot::SmartEnergyActualCurrent |
| class | youbot::SmartEnergyCurrentDownStep |
| class | youbot::SmartEnergyCurrentMinimum |
| class | youbot::SmartEnergyCurrentUpStep |
| class | youbot::SmartEnergyHysteresis |
| class | youbot::SmartEnergyHysteresisStart |
| The lower threshold for the stallGuard2 value (see smart Energy current up step). More... | |
| class | youbot::SmartEnergySlowRunCurrent |
| Sets the motor current which is used below the threshold speed. More... | |
| class | youbot::SmartEnergyThresholdSpeed |
| Above this speed coolStep becomes enabled. More... | |
| class | youbot::StallGuard2FilterEnable |
| class | youbot::StallGuard2Threshold |
| class | youbot::StandbyCurrent |
| The current limit two seconds after the motor has stopped. More... | |
| class | youbot::StepInterpolationEnable |
| class | youbot::StopOnStall |
| Motor stop in case of stall. More... | |
| class | youbot::TargetPositionReached |
| Indicates that the actual position equals the target position. More... | |
| class | youbot::VelocitySetpoint |
| Velocity setpoint for one gripper bar. More... | |
| class | youbot::Vsense |
| class | youbot::YouBotGripperParameter |
| abstract youBot gripper parameter More... | |
Namespaces | |
| youbot | |