#include <YouBotJoint.hpp>

Public Member Functions | |
| virtual void | getConfigurationParameter (YouBotJointParameterReadOnly ¶meter) |
| virtual void | getConfigurationParameter (YouBotJointParameter ¶meter) |
| virtual void | getConfigurationParameter (JointName ¶meter) |
| virtual void | getConfigurationParameter (GearRatio ¶meter) |
| virtual void | getConfigurationParameter (EncoderTicksPerRound ¶meter) |
| virtual void | getConfigurationParameter (InverseMovementDirection ¶meter) |
| virtual void | getConfigurationParameter (JointLimits ¶meter) |
| virtual void | getConfigurationParameter (JointLimitsRadian ¶meter) |
| virtual void | getConfigurationParameter (FirmwareVersion ¶meter) |
| virtual void | getConfigurationParameter (YouBotSlaveMailboxMsg ¶meter) |
| this method should be only used if you know what you are doing | |
| virtual void | getConfigurationParameter (TorqueConstant ¶meter) |
| virtual void | getData (JointSensedAngle &data) |
| virtual void | getData (JointSensedVelocity &data) |
| virtual void | getData (JointSensedRoundsPerMinute &data) |
| virtual void | getData (JointSensedCurrent &data) |
| virtual void | getData (JointSensedEncoderTicks &data) |
| virtual void | getData (YouBotSlaveMsg &data) |
| virtual void | getData (JointSensedTorque &data) |
| virtual void | getData (JointAngleSetpoint &data) |
| virtual void | getData (JointVelocitySetpoint &data) |
| virtual void | getData (JointCurrentSetpoint &data) |
| virtual void | getData (JointRampGeneratorVelocity &data) |
| unsigned int | getJointNumber () |
| virtual void | getStatus (std::vector< std::string > &statusMessages) |
| Returns the status messages for the motor controller. | |
| virtual void | getStatus (unsigned int &statusFlags) |
| void | getUserVariable (const unsigned int index, int &data) |
| void | noMoreAction () |
| void | restoreConfigurationParameter (YouBotJointParameter ¶meter) |
| Restores the joint parameter from the EEPROM. | |
| virtual void | setConfigurationParameter (const YouBotJointParameter ¶meter) |
| virtual void | setConfigurationParameter (const JointName ¶meter) |
| virtual void | setConfigurationParameter (const GearRatio ¶meter) |
| virtual void | setConfigurationParameter (const EncoderTicksPerRound ¶meter) |
| virtual void | setConfigurationParameter (const CalibrateJoint ¶meter) |
| virtual void | setConfigurationParameter (const InverseMovementDirection ¶meter) |
| virtual void | setConfigurationParameter (const JointLimits ¶meter) |
| virtual void | setConfigurationParameter (const InitializeJoint ¶meter) |
| commutation method for firmware 1.48 and below | |
| virtual void | setConfigurationParameter (const YouBotSlaveMailboxMsg ¶meter) |
| this method should be only used if you know what you are doing | |
| virtual void | setConfigurationParameter (const TorqueConstant ¶meter) |
| virtual void | setData (const JointAngleSetpoint &data) |
| virtual void | setData (const JointEncoderSetpoint &data) |
| virtual void | setData (const JointVelocitySetpoint &data) |
| virtual void | setData (const JointRoundsPerMinuteSetpoint &data) |
| virtual void | setData (const JointCurrentSetpoint &data) |
| virtual void | setData (const SlaveMessageOutput &data) |
| virtual void | setData (const JointTorqueSetpoint &data) |
| void | setEncoderToZero () |
| set the encoder values of the joint to zero. This postion will be the new reference. | |
| void | setUserVariable (const unsigned int index, const int data) |
| void | stopJoint () |
| void | storeConfigurationParameterPermanent (const YouBotJointParameter ¶meter) |
| YouBotJoint (const unsigned int jointNo, const std::string &configFilePath) | |
| ~YouBotJoint () | |
Public Attributes | |
| JointTrajectoryController | trajectoryController |
Protected Member Functions | |
| virtual void | getConfigurationParameter (JointParameter ¶meter) |
| virtual void | getData (JointData &data) |
| virtual void | setConfigurationParameter (const JointParameter ¶meter) |
| virtual void | setData (const JointDataSetpoint &data) |
Private Member Functions | |
| YouBotJoint & | operator= (const YouBotJoint &source) |
| void | parseMailboxStatusFlags (const YouBotSlaveMailboxMsg &mailboxMsg) |
| void | parseYouBotErrorFlags (const YouBotSlaveMsg &messageBuffer) |
| bool | retrieveValueFromMotorContoller (YouBotSlaveMailboxMsg &message) |
| bool | setValueToMotorContoller (const YouBotSlaveMailboxMsg &mailboxMsg) |
| YouBotJoint (const YouBotJoint &source) | |
Private Attributes | |
| EthercatMasterInterface * | ethercatMaster |
| quantity< plane_angle > | lastPosition |
| quantity< si::angular_velocity > | lastVelocity |
| boost::scoped_ptr < JointLimitMonitor > | limitMonitor |
| unsigned int | mailboxMsgRetries |
| YouBotSlaveMsg | messageBuffer |
| bool | positionReferenceToZero |
| YouBotJointStorage | storage |
| unsigned int | timeTillNextMailboxUpdate |
youBot joint for the base and the manipulator. Every motor, encoder, transmition combination of the youBot base or manipulator is a YouBotJoint
Definition at line 85 of file YouBotJoint.hpp.
| youbot::YouBotJoint::YouBotJoint | ( | const unsigned int | jointNo, |
| const std::string & | configFilePath | ||
| ) |
Definition at line 55 of file YouBotJoint.cpp.
Definition at line 73 of file YouBotJoint.cpp.
| youbot::YouBotJoint::YouBotJoint | ( | const YouBotJoint & | source | ) | [private] |
| void youbot::YouBotJoint::getConfigurationParameter | ( | JointParameter & | parameter | ) | [protected, virtual] |
Implements youbot::Joint.
Definition at line 86 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | YouBotJointParameterReadOnly & | parameter | ) | [virtual] |
Definition at line 93 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | YouBotJointParameter & | parameter | ) | [virtual] |
Definition at line 122 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | JointName & | parameter | ) | [virtual] |
Definition at line 174 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | GearRatio & | parameter | ) | [virtual] |
Definition at line 188 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | EncoderTicksPerRound & | parameter | ) | [virtual] |
Definition at line 206 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | InverseMovementDirection & | parameter | ) | [virtual] |
Definition at line 298 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | JointLimits & | parameter | ) | [virtual] |
Definition at line 331 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | JointLimitsRadian & | parameter | ) | [virtual] |
Definition at line 338 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | FirmwareVersion & | parameter | ) | [virtual] |
Definition at line 363 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | YouBotSlaveMailboxMsg & | parameter | ) | [virtual] |
this method should be only used if you know what you are doing
Definition at line 434 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getConfigurationParameter | ( | TorqueConstant & | parameter | ) | [virtual] |
Definition at line 445 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointData & | data | ) | [protected, virtual] |
Implements youbot::Joint.
Definition at line 519 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointSensedAngle & | data | ) | [virtual] |
gets the position or angle of one joint which have been calculated from the actual encoder value
| data | returns the angle by reference |
Definition at line 599 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointSensedVelocity & | data | ) | [virtual] |
gets the velocity of one joint
| data | returns the velocity by reference |
Definition at line 665 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointSensedRoundsPerMinute & | data | ) | [virtual] |
gets the velocity in round per minute of one joint
| data | returns the velocity by reference |
Definition at line 694 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointSensedCurrent & | data | ) | [virtual] |
gets the motor current of one joint which have been measured by a hal sensor
| data | returns the actual motor current by reference |
Definition at line 743 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointSensedEncoderTicks & | data | ) | [virtual] |
gets the encoder ticks of one joint
| data | returns the ticks by reference |
Definition at line 792 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | YouBotSlaveMsg & | data | ) | [virtual] |
gets the input and ouput part of a EtherCAT slave message this methode should be only used if you know what you are doing
| data | returns the sensor values by reference |
Definition at line 839 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointSensedTorque & | data | ) | [virtual] |
gets the motor torque of one joint which have been calculated from the current
| data | returns the actual motor torque by reference |
Definition at line 879 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointAngleSetpoint & | data | ) | [virtual] |
gets the target or setpoint position of one joint (only firmware 2.0 or higher)
| data | returns the angle by reference |
Definition at line 901 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointVelocitySetpoint & | data | ) | [virtual] |
gets the target or setpoint velocity of one joint (only firmware 2.0 or higher)
| data | returns the velocity by reference |
Definition at line 934 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointCurrentSetpoint & | data | ) | [virtual] |
gets the motor current target or setpoint of one joint (only firmware 2.0 or higher)
| data | returns the motor current by reference |
Definition at line 963 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getData | ( | JointRampGeneratorVelocity & | data | ) | [virtual] |
gets the ramp generator velocity of one joint (only firmware 2.0 or higher)
| data | returns the velocity by reference |
Definition at line 987 of file YouBotJoint.cpp.
| unsigned int youbot::YouBotJoint::getJointNumber | ( | ) |
Definition at line 1249 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getStatus | ( | std::vector< std::string > & | statusMessages | ) | [virtual] |
Returns the status messages for the motor controller.
Definition at line 1065 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getStatus | ( | unsigned int & | statusFlags | ) | [virtual] |
Returns the status messages as status flags for the motor controller. The status flag bits are assigned like this: 0: Overcurrent 1: Undervoltage 2: Overvoltage 3: Overtemperature 4: Motor halted 5: Hall error flag 6: --- 7: --- 8: PWM mode active 9: Velocity mode active 10: Position mode active 11: Torque mode active 12: --- 13: --- 14: Position end flag 15: Module initialized 16: EtherCAT timeout flag 17: I2t exceeded flag
Definition at line 1178 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::getUserVariable | ( | const unsigned int | index, |
| int & | data | ||
| ) |
Definition at line 1014 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::noMoreAction | ( | ) |
Definition at line 1217 of file YouBotJoint.cpp.
| YouBotJoint& youbot::YouBotJoint::operator= | ( | const YouBotJoint & | source | ) | [private] |
| void youbot::YouBotJoint::parseMailboxStatusFlags | ( | const YouBotSlaveMailboxMsg & | mailboxMsg | ) | [private] |
Definition at line 1366 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::parseYouBotErrorFlags | ( | const YouBotSlaveMsg & | messageBuffer | ) | [private] |
Definition at line 1256 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::restoreConfigurationParameter | ( | YouBotJointParameter & | parameter | ) |
Restores the joint parameter from the EEPROM.
Definition at line 487 of file YouBotJoint.cpp.
| bool youbot::YouBotJoint::retrieveValueFromMotorContoller | ( | YouBotSlaveMailboxMsg & | message | ) | [private] |
Definition at line 1408 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const JointParameter & | parameter | ) | [protected, virtual] |
Implements youbot::Joint.
Definition at line 79 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const YouBotJointParameter & | parameter | ) | [virtual] |
Definition at line 150 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const JointName & | parameter | ) | [virtual] |
Definition at line 181 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const GearRatio & | parameter | ) | [virtual] |
Definition at line 195 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const EncoderTicksPerRound & | parameter | ) | [virtual] |
Definition at line 213 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const CalibrateJoint & | parameter | ) | [virtual] |
Definition at line 224 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const InverseMovementDirection & | parameter | ) | [virtual] |
Definition at line 291 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const JointLimits & | parameter | ) | [virtual] |
Definition at line 305 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const InitializeJoint & | parameter | ) | [virtual] |
commutation method for firmware 1.48 and below
Definition at line 350 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const YouBotSlaveMailboxMsg & | parameter | ) | [virtual] |
this method should be only used if you know what you are doing
Definition at line 423 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setConfigurationParameter | ( | const TorqueConstant & | parameter | ) | [virtual] |
Definition at line 452 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointDataSetpoint & | data | ) | [protected, virtual] |
Implements youbot::Joint.
Definition at line 512 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointAngleSetpoint & | data | ) | [virtual] |
commands a position or angle to one joint
| data | the to command position |
Definition at line 528 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointEncoderSetpoint & | data | ) | [virtual] |
commands a encoder value (position) to one joint
| data | the to command encoder value |
Definition at line 569 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointVelocitySetpoint & | data | ) | [virtual] |
commands a velocity to one joint
| data | the to command velocity |
Definition at line 632 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointRoundsPerMinuteSetpoint & | data | ) | [virtual] |
sets the velocity in round per minute to one joint
| data | the setpoint velocity |
Definition at line 717 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointCurrentSetpoint & | data | ) | [virtual] |
commands a current to one joint
| data | the to command current |
Definition at line 767 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const SlaveMessageOutput & | data | ) | [virtual] |
sets the output part of a EtherCAT slave message this methode should be only used if you know what you are doing
| data | output part of a EtherCAT slave message |
Definition at line 818 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setData | ( | const JointTorqueSetpoint & | data | ) | [virtual] |
commands a torque to one joint
| data | the to command torque |
Definition at line 857 of file YouBotJoint.cpp.
set the encoder values of the joint to zero. This postion will be the new reference.
Definition at line 1189 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::setUserVariable | ( | const unsigned int | index, |
| const int | data | ||
| ) |
Definition at line 1040 of file YouBotJoint.cpp.
| bool youbot::YouBotJoint::setValueToMotorContoller | ( | const YouBotSlaveMailboxMsg & | mailboxMsg | ) | [private] |
Definition at line 1452 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::stopJoint | ( | ) |
Definition at line 1233 of file YouBotJoint.cpp.
| void youbot::YouBotJoint::storeConfigurationParameterPermanent | ( | const YouBotJointParameter & | parameter | ) |
stores the joint parameter permanent in the EEPROM of the motor contoller Attentions: The EEPROM has only a finite number of program-erase cycles
Definition at line 461 of file YouBotJoint.cpp.
Definition at line 285 of file YouBotJoint.hpp.
quantity<plane_angle> youbot::YouBotJoint::lastPosition [private] |
Definition at line 299 of file YouBotJoint.hpp.
quantity<si::angular_velocity> youbot::YouBotJoint::lastVelocity [private] |
Definition at line 297 of file YouBotJoint.hpp.
boost::scoped_ptr<JointLimitMonitor> youbot::YouBotJoint::limitMonitor [private] |
Definition at line 301 of file YouBotJoint.hpp.
unsigned int youbot::YouBotJoint::mailboxMsgRetries [private] |
Definition at line 291 of file YouBotJoint.hpp.
Definition at line 295 of file YouBotJoint.hpp.
bool youbot::YouBotJoint::positionReferenceToZero [private] |
Definition at line 287 of file YouBotJoint.hpp.
Definition at line 293 of file YouBotJoint.hpp.
unsigned int youbot::YouBotJoint::timeTillNextMailboxUpdate [private] |
Definition at line 289 of file YouBotJoint.hpp.
Definition at line 282 of file YouBotJoint.hpp.