Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
youbot::YouBotJointParameter Class Referenceabstract

abstract youBot joint parameter More...

#include <YouBotJointParameter.hpp>

Inheritance diagram for youbot::YouBotJointParameter:
Inheritance graph
[legend]

Public Member Functions

virtual void toString (std::string &value)=0
 
virtual ~YouBotJointParameter ()
 
- Public Member Functions inherited from youbot::YouBotJointParameterReadOnly
virtual ~YouBotJointParameterReadOnly ()
 

Protected Member Functions

virtual std::string getName () const =0
 
virtual ParameterType getType () const =0
 
virtual void getYouBotMailboxMsg (YouBotSlaveMailboxMsg &message, TMCLCommandNumber msgType, const YouBotJointStorage &storage) const =0
 
virtual void setYouBotMailboxMsg (const YouBotSlaveMailboxMsg &message, const YouBotJointStorage &storage)=0
 
 YouBotJointParameter ()
 
- Protected Member Functions inherited from youbot::YouBotJointParameterReadOnly
 YouBotJointParameterReadOnly ()
 

Protected Attributes

std::string name
 
ParameterType parameterType
 
- Protected Attributes inherited from youbot::YouBotJointParameterReadOnly
std::string name
 
ParameterType parameterType
 

Friends

class YouBotJoint
 

Detailed Description

abstract youBot joint parameter

Definition at line 95 of file YouBotJointParameter.hpp.

Constructor & Destructor Documentation

youbot::YouBotJointParameter::YouBotJointParameter ( )
protected

Definition at line 64 of file YouBotJointParameter.cpp.

youbot::YouBotJointParameter::~YouBotJointParameter ( )
virtual

Definition at line 69 of file YouBotJointParameter.cpp.

Member Function Documentation

virtual std::string youbot::YouBotJointParameter::getName ( ) const
protectedpure virtual

Implements youbot::YouBotJointParameterReadOnly.

Implemented in youbot::ClearMotorControllerTimeoutFlag, youbot::ClearI2tExceededFlag, youbot::PositionTargetReachedDistance, youbot::MaximumVelocityToSetPosition, youbot::IClippingParameterCurrentControl, youbot::DParameterCurrentControl, youbot::IParameterCurrentControl, youbot::PParameterCurrentControl, youbot::IClippingParameterSecondParametersSpeedControl, youbot::DParameterSecondParametersSpeedControl, youbot::IParameterSecondParametersSpeedControl, youbot::MotorHaltedVelocity, youbot::PParameterSecondParametersSpeedControl, youbot::ThermalWindingTimeConstant, youbot::IClippingParameterSecondParametersPositionControl, youbot::StopSwitchPolarity, youbot::DParameterSecondParametersPositionControl, youbot::IParameterSecondParametersPositionControl, youbot::SineInitializationVelocity, youbot::PParameterSecondParametersPositionControl, youbot::SetEncoderCounterZeroOnlyOnce, youbot::SetEncoderCounterZeroAtNextSwitch, youbot::IClippingParameterFirstParametersSpeedControl, youbot::SetEncoderCounterZeroAtNextNChannel, youbot::DParameterFirstParametersSpeedControl, youbot::ReversingEncoderDirection, youbot::IParameterFirstParametersSpeedControl, youbot::PIDControlTime, youbot::PParameterFirstParametersSpeedControl, youbot::OperationalTime, youbot::IClippingParameterFirstParametersPositionControl, youbot::MotorPoles, youbot::DParameterFirstParametersPositionControl, youbot::MotorControllerTimeout, youbot::IParameterFirstParametersPositionControl, youbot::MotorCoilResistance, youbot::PParameterFirstParametersPositionControl, youbot::MaximumMotorCurrent, youbot::VelocityThresholdForHallFX, youbot::MassInertiaConstant, youbot::SpeedControlSwitchingThreshold, youbot::InitSineDelay, youbot::PositionControlSwitchingThreshold, youbot::InitializationMode, youbot::RampGeneratorSpeedAndPositionControl, youbot::I2tLimit, youbot::MotorAcceleration, youbot::I2tExceedCounter, youbot::MaximumPositioningVelocity, youbot::HallSensorPolarityReversal, youbot::EncoderStopSwitch, youbot::EncoderResolution, youbot::CurrentControlLoopDelay, youbot::CommutationMotorCurrent, youbot::CommutationMode, youbot::BEMFConstant, youbot::ApproveProtectedParameters, youbot::InitializeJoint, youbot::ActualCommutationOffset, youbot::ActivateOvervoltageProtection, and youbot::YouBotJointParameterPasswordProtected.

virtual ParameterType youbot::YouBotJointParameter::getType ( ) const
protectedpure virtual

Implements youbot::YouBotJointParameterReadOnly.

Implemented in youbot::ClearMotorControllerTimeoutFlag, youbot::ClearI2tExceededFlag, youbot::PositionTargetReachedDistance, youbot::MaximumVelocityToSetPosition, youbot::IClippingParameterCurrentControl, youbot::DParameterCurrentControl, youbot::IParameterCurrentControl, youbot::PParameterCurrentControl, youbot::IClippingParameterSecondParametersSpeedControl, youbot::DParameterSecondParametersSpeedControl, youbot::IParameterSecondParametersSpeedControl, youbot::MotorHaltedVelocity, youbot::PParameterSecondParametersSpeedControl, youbot::ThermalWindingTimeConstant, youbot::IClippingParameterSecondParametersPositionControl, youbot::StopSwitchPolarity, youbot::DParameterSecondParametersPositionControl, youbot::IParameterSecondParametersPositionControl, youbot::SineInitializationVelocity, youbot::PParameterSecondParametersPositionControl, youbot::SetEncoderCounterZeroOnlyOnce, youbot::SetEncoderCounterZeroAtNextSwitch, youbot::IClippingParameterFirstParametersSpeedControl, youbot::SetEncoderCounterZeroAtNextNChannel, youbot::DParameterFirstParametersSpeedControl, youbot::ReversingEncoderDirection, youbot::IParameterFirstParametersSpeedControl, youbot::PIDControlTime, youbot::PParameterFirstParametersSpeedControl, youbot::OperationalTime, youbot::IClippingParameterFirstParametersPositionControl, youbot::MotorPoles, youbot::DParameterFirstParametersPositionControl, youbot::MotorControllerTimeout, youbot::IParameterFirstParametersPositionControl, youbot::MotorCoilResistance, youbot::PParameterFirstParametersPositionControl, youbot::MaximumMotorCurrent, youbot::VelocityThresholdForHallFX, youbot::MassInertiaConstant, youbot::SpeedControlSwitchingThreshold, youbot::InitSineDelay, youbot::PositionControlSwitchingThreshold, youbot::InitializationMode, youbot::RampGeneratorSpeedAndPositionControl, youbot::I2tLimit, youbot::MotorAcceleration, youbot::I2tExceedCounter, youbot::MaximumPositioningVelocity, youbot::HallSensorPolarityReversal, youbot::EncoderStopSwitch, youbot::EncoderResolution, youbot::CurrentControlLoopDelay, youbot::CommutationMotorCurrent, youbot::CommutationMode, youbot::BEMFConstant, youbot::ApproveProtectedParameters, youbot::InitializeJoint, youbot::ActualCommutationOffset, youbot::ActivateOvervoltageProtection, and youbot::YouBotJointParameterPasswordProtected.

virtual void youbot::YouBotJointParameter::getYouBotMailboxMsg ( YouBotSlaveMailboxMsg message,
TMCLCommandNumber  msgType,
const YouBotJointStorage storage 
) const
protectedpure virtual

Implements youbot::YouBotJointParameterReadOnly.

Implemented in youbot::ClearMotorControllerTimeoutFlag, youbot::ClearI2tExceededFlag, youbot::PositionTargetReachedDistance, youbot::MaximumVelocityToSetPosition, youbot::IClippingParameterCurrentControl, youbot::DParameterCurrentControl, youbot::IParameterCurrentControl, youbot::PParameterCurrentControl, youbot::IClippingParameterSecondParametersSpeedControl, youbot::DParameterSecondParametersSpeedControl, youbot::IParameterSecondParametersSpeedControl, youbot::MotorHaltedVelocity, youbot::PParameterSecondParametersSpeedControl, youbot::ThermalWindingTimeConstant, youbot::IClippingParameterSecondParametersPositionControl, youbot::StopSwitchPolarity, youbot::DParameterSecondParametersPositionControl, youbot::IParameterSecondParametersPositionControl, youbot::SineInitializationVelocity, youbot::PParameterSecondParametersPositionControl, youbot::SetEncoderCounterZeroOnlyOnce, youbot::SetEncoderCounterZeroAtNextSwitch, youbot::IClippingParameterFirstParametersSpeedControl, youbot::SetEncoderCounterZeroAtNextNChannel, youbot::DParameterFirstParametersSpeedControl, youbot::ReversingEncoderDirection, youbot::IParameterFirstParametersSpeedControl, youbot::PIDControlTime, youbot::PParameterFirstParametersSpeedControl, youbot::OperationalTime, youbot::IClippingParameterFirstParametersPositionControl, youbot::MotorPoles, youbot::DParameterFirstParametersPositionControl, youbot::MotorControllerTimeout, youbot::IParameterFirstParametersPositionControl, youbot::MotorCoilResistance, youbot::PParameterFirstParametersPositionControl, youbot::MaximumMotorCurrent, youbot::VelocityThresholdForHallFX, youbot::MassInertiaConstant, youbot::SpeedControlSwitchingThreshold, youbot::InitSineDelay, youbot::PositionControlSwitchingThreshold, youbot::InitializationMode, youbot::RampGeneratorSpeedAndPositionControl, youbot::I2tLimit, youbot::MotorAcceleration, youbot::I2tExceedCounter, youbot::MaximumPositioningVelocity, youbot::HallSensorPolarityReversal, youbot::EncoderStopSwitch, youbot::EncoderResolution, youbot::CurrentControlLoopDelay, youbot::CommutationMotorCurrent, youbot::CommutationMode, youbot::BEMFConstant, youbot::ApproveProtectedParameters, youbot::InitializeJoint, youbot::ActualCommutationOffset, youbot::ActivateOvervoltageProtection, and youbot::YouBotJointParameterPasswordProtected.

virtual void youbot::YouBotJointParameter::setYouBotMailboxMsg ( const YouBotSlaveMailboxMsg message,
const YouBotJointStorage storage 
)
protectedpure virtual

Implements youbot::YouBotJointParameterReadOnly.

Implemented in youbot::ClearMotorControllerTimeoutFlag, youbot::ClearI2tExceededFlag, youbot::PositionTargetReachedDistance, youbot::MaximumVelocityToSetPosition, youbot::IClippingParameterCurrentControl, youbot::DParameterCurrentControl, youbot::IParameterCurrentControl, youbot::PParameterCurrentControl, youbot::IClippingParameterSecondParametersSpeedControl, youbot::DParameterSecondParametersSpeedControl, youbot::IParameterSecondParametersSpeedControl, youbot::MotorHaltedVelocity, youbot::PParameterSecondParametersSpeedControl, youbot::ThermalWindingTimeConstant, youbot::IClippingParameterSecondParametersPositionControl, youbot::StopSwitchPolarity, youbot::DParameterSecondParametersPositionControl, youbot::IParameterSecondParametersPositionControl, youbot::SineInitializationVelocity, youbot::PParameterSecondParametersPositionControl, youbot::SetEncoderCounterZeroOnlyOnce, youbot::SetEncoderCounterZeroAtNextSwitch, youbot::IClippingParameterFirstParametersSpeedControl, youbot::SetEncoderCounterZeroAtNextNChannel, youbot::DParameterFirstParametersSpeedControl, youbot::ReversingEncoderDirection, youbot::IParameterFirstParametersSpeedControl, youbot::PIDControlTime, youbot::PParameterFirstParametersSpeedControl, youbot::OperationalTime, youbot::IClippingParameterFirstParametersPositionControl, youbot::MotorPoles, youbot::DParameterFirstParametersPositionControl, youbot::MotorControllerTimeout, youbot::IParameterFirstParametersPositionControl, youbot::MotorCoilResistance, youbot::PParameterFirstParametersPositionControl, youbot::MaximumMotorCurrent, youbot::VelocityThresholdForHallFX, youbot::MassInertiaConstant, youbot::SpeedControlSwitchingThreshold, youbot::InitSineDelay, youbot::PositionControlSwitchingThreshold, youbot::InitializationMode, youbot::RampGeneratorSpeedAndPositionControl, youbot::I2tLimit, youbot::MotorAcceleration, youbot::I2tExceedCounter, youbot::MaximumPositioningVelocity, youbot::HallSensorPolarityReversal, youbot::EncoderStopSwitch, youbot::EncoderResolution, youbot::CurrentControlLoopDelay, youbot::CommutationMotorCurrent, youbot::CommutationMode, youbot::BEMFConstant, youbot::ApproveProtectedParameters, youbot::InitializeJoint, youbot::ActualCommutationOffset, youbot::ActivateOvervoltageProtection, and youbot::YouBotJointParameterPasswordProtected.

virtual void youbot::YouBotJointParameter::toString ( std::string &  value)
pure virtual

Implements youbot::YouBotJointParameterReadOnly.

Implemented in youbot::ClearMotorControllerTimeoutFlag, youbot::ClearI2tExceededFlag, youbot::PositionTargetReachedDistance, youbot::MaximumVelocityToSetPosition, youbot::IClippingParameterCurrentControl, youbot::DParameterCurrentControl, youbot::IParameterCurrentControl, youbot::PParameterCurrentControl, youbot::IClippingParameterSecondParametersSpeedControl, youbot::DParameterSecondParametersSpeedControl, youbot::IParameterSecondParametersSpeedControl, youbot::MotorHaltedVelocity, youbot::PParameterSecondParametersSpeedControl, youbot::ThermalWindingTimeConstant, youbot::IClippingParameterSecondParametersPositionControl, youbot::StopSwitchPolarity, youbot::DParameterSecondParametersPositionControl, youbot::IParameterSecondParametersPositionControl, youbot::SineInitializationVelocity, youbot::PParameterSecondParametersPositionControl, youbot::SetEncoderCounterZeroOnlyOnce, youbot::SetEncoderCounterZeroAtNextSwitch, youbot::IClippingParameterFirstParametersSpeedControl, youbot::SetEncoderCounterZeroAtNextNChannel, youbot::DParameterFirstParametersSpeedControl, youbot::ReversingEncoderDirection, youbot::IParameterFirstParametersSpeedControl, youbot::PIDControlTime, youbot::PParameterFirstParametersSpeedControl, youbot::OperationalTime, youbot::IClippingParameterFirstParametersPositionControl, youbot::MotorPoles, youbot::DParameterFirstParametersPositionControl, youbot::MotorControllerTimeout, youbot::IParameterFirstParametersPositionControl, youbot::MotorCoilResistance, youbot::PParameterFirstParametersPositionControl, youbot::MaximumMotorCurrent, youbot::VelocityThresholdForHallFX, youbot::MassInertiaConstant, youbot::SpeedControlSwitchingThreshold, youbot::InitSineDelay, youbot::PositionControlSwitchingThreshold, youbot::InitializationMode, youbot::RampGeneratorSpeedAndPositionControl, youbot::I2tLimit, youbot::MotorAcceleration, youbot::I2tExceedCounter, youbot::MaximumPositioningVelocity, youbot::HallSensorPolarityReversal, youbot::EncoderStopSwitch, youbot::EncoderResolution, youbot::CurrentControlLoopDelay, youbot::CommutationMotorCurrent, youbot::CommutationMode, youbot::BEMFConstant, youbot::ApproveProtectedParameters, youbot::InitializeJoint, youbot::ActualCommutationOffset, youbot::ActivateOvervoltageProtection, and youbot::YouBotJointParameterPasswordProtected.

Friends And Related Function Documentation

friend class YouBotJoint
friend

Definition at line 96 of file YouBotJointParameter.hpp.

Member Data Documentation

std::string youbot::YouBotJointParameter::name
protected

Definition at line 116 of file YouBotJointParameter.hpp.

ParameterType youbot::YouBotJointParameter::parameterType
protected

Definition at line 118 of file YouBotJointParameter.hpp.


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


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:27