

Go to the source code of this file.
Classes | |
| class | youbot::CalibrateJoint |
| calibrates the joint More... | |
| class | youbot::ClearI2tExceededFlag |
| Clear the flag that indicates that the I2t sum has exceeded the I2t limit. More... | |
| class | youbot::ClearMotorControllerTimeoutFlag |
| Clear the flag that indicates a communication timeout between the EtherCAT master and the controller. More... | |
| class | youbot::DParameterCurrentControl |
| D-Parameter of PID current regulator. More... | |
| class | youbot::DParameterFirstParametersPositionControl |
| D-Parameter of PID position regulator (first position parameter set) More... | |
| class | youbot::DParameterFirstParametersSpeedControl |
| D-Parameter of PID velocity regulator. This PID parameter set is used at lower velocity. (first velocity parameter set) More... | |
| class | youbot::DParameterSecondParametersPositionControl |
| D-Parameter of PID position regulator (second position parameter set) More... | |
| class | youbot::DParameterSecondParametersSpeedControl |
| D-Parameter of PID velocity regulator (second position parameter set) More... | |
| class | youbot::DParameterTrajectoryControl |
| D-Parameter of PID trajectory regulator. More... | |
| class | youbot::EncoderTicksPerRound |
| the resolution of the encoders, it is needed for the calculations of the youBot Driver More... | |
| class | youbot::FirmwareVersion |
| the firmware version of the joint More... | |
| class | youbot::GearRatio |
| the gear ratio which is needed for the calculations in the youBot driver More... | |
| class | youbot::IClippingParameterCurrentControl |
| I-Clipping Parameter of PID current regulator. More... | |
| class | youbot::IClippingParameterFirstParametersPositionControl |
| Adjust in standstill to lowest possible value at which the motor keeps its position. A too high value causes overshooting at positioning mode. (first position parameter set) More... | |
| class | youbot::IClippingParameterFirstParametersSpeedControl |
| This PID parameter set is used at lower velocity. (first velocity parameter set) More... | |
| class | youbot::IClippingParameterSecondParametersPositionControl |
| Adjust in standstill to lowest possible value at which the motor keeps its position. A too high value causes overshooting at positioning mode. (second position parameter set) More... | |
| class | youbot::IClippingParameterSecondParametersSpeedControl |
| I-Clipping Parameter of PID current regulator. This PID parameter set is used at lower velocity. (second position parameter set) More... | |
| class | youbot::IClippingParameterTrajectoryControl |
| gives a limit for the I sum part of the trajectory regulator More... | |
| class | youbot::InitializeJoint |
| Initialize Joint. More... | |
| class | youbot::InverseMovementDirection |
| inverse the joint movement direction More... | |
| class | youbot::IParameterCurrentControl |
| I-Parameter of PID current regulator. More... | |
| class | youbot::IParameterFirstParametersPositionControl |
| I-Parameter of PID position regulator (first position parameter set) More... | |
| class | youbot::IParameterFirstParametersSpeedControl |
| I-Parameter of PID velocity regulator. This PID parameter set is used at lower velocity. (first velocity parameter set) More... | |
| class | youbot::IParameterSecondParametersPositionControl |
| I-Parameter of PID position regulator (second position parameter set) More... | |
| class | youbot::IParameterSecondParametersSpeedControl |
| I-Parameter of PID velocity regulator (second position parameter set) More... | |
| class | youbot::IParameterTrajectoryControl |
| I-Parameter of PID trajectory regulator. More... | |
| class | youbot::JointLimits |
| joint position limits in encoder ticks More... | |
| class | youbot::JointLimitsRadian |
| joint position limits in radian More... | |
| class | youbot::JointName |
| the name of the joint More... | |
| class | youbot::MaximumPositioningVelocity |
| The maximum velocity used for move to position command when executing a ramp to a position. In sensorless commutation mode the velocity threshold for hallFX. In sensorless commutation mode used as velocity threshold for hallFXTM. Set this value to a realistic velocity which the motor can reach! More... | |
| class | youbot::MaximumVelocityToSetPosition |
| Maximum velocity at which end position can be set. Prevents issuing of end position when the target is passed at high velocity. More... | |
| class | youbot::MotorAcceleration |
| Acceleration parameter for velocity control and position control. More... | |
| class | youbot::PositionControlSwitchingThreshold |
| Switching threshold for position control between the first and second set of parameters. If the velocity threshold is set to zero, the parameter set 2 is used all the time. More... | |
| class | youbot::PositionTargetReachedDistance |
| Maximum distance at which the position end flag is set. More... | |
| class | youbot::PParameterCurrentControl |
| P-Parameter of PID current regulator. More... | |
| class | youbot::PParameterFirstParametersPositionControl |
| P-Parameter of PID position regulator (first position parameter set) More... | |
| class | youbot::PParameterFirstParametersSpeedControl |
| P-Parameter of PID velocity regulator. This PID parameter set is used at lower velocity. (first velocity parameter set) More... | |
| class | youbot::PParameterSecondParametersPositionControl |
| P-Parameter of PID position regulator (second position parameter set) More... | |
| class | youbot::PParameterSecondParametersSpeedControl |
| P-Parameter of PID velocity regulator (second position parameter set) More... | |
| class | youbot::PParameterTrajectoryControl |
| P-Parameter of PID trajectory regulator. More... | |
| class | youbot::RampGeneratorSpeedAndPositionControl |
| Switches the ramp generator for speed and position control on and off. More... | |
| class | youbot::SpeedControlSwitchingThreshold |
| Adjusts the limit to switch between first velocity PID parameter set and second velocity PID parameter set. If the velocity threshold is set to zero, the parameter set 2 is used all the time. More... | |
| class | youbot::TorqueConstant |
| the resolution of the encoders, it is needed for the calculations of the youBot Driver More... | |
| class | youbot::VelocityThresholdForHallFX |
| Velocity to switch from controlled to hallFX mode. Set this value to a realistic velocity which the motor can reach in controlled mode! More... | |
| class | youbot::YouBotApiJointParameter |
| abstract youBot API joint parameter More... | |
| class | youbot::YouBotJointParameter |
| abstract youBot joint parameter More... | |
Namespaces | |
| youbot | |
Enumerations | |
| enum | youbot::CalibrationDirection { youbot::POSITIV, youbot::NEGATIV } |