#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 More... | |
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. More... | |
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. More... | |
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 More... | |
virtual void | setConfigurationParameter (const YouBotSlaveMailboxMsg ¶meter) |
this method should be only used if you know what you are doing More... | |
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. More... | |
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="../config/") | |
~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 77 of file YouBotJoint.hpp.
youbot::YouBotJoint::YouBotJoint | ( | const unsigned int | jointNo, |
const std::string & | configFilePath = "../config/" |
||
) |
Definition at line 55 of file YouBotJoint.cpp.
youbot::YouBotJoint::~YouBotJoint | ( | ) |
Definition at line 72 of file YouBotJoint.cpp.
|
private |
|
protectedvirtual |
Implements youbot::Joint.
Definition at line 83 of file YouBotJoint.cpp.
|
virtual |
Definition at line 89 of file YouBotJoint.cpp.
|
virtual |
Definition at line 109 of file YouBotJoint.cpp.
|
virtual |
Definition at line 145 of file YouBotJoint.cpp.
|
virtual |
Definition at line 157 of file YouBotJoint.cpp.
|
virtual |
Definition at line 172 of file YouBotJoint.cpp.
|
virtual |
Definition at line 251 of file YouBotJoint.cpp.
|
virtual |
Definition at line 281 of file YouBotJoint.cpp.
|
virtual |
Definition at line 287 of file YouBotJoint.cpp.
|
virtual |
Definition at line 307 of file YouBotJoint.cpp.
|
virtual |
this method should be only used if you know what you are doing
Definition at line 369 of file YouBotJoint.cpp.
|
virtual |
Definition at line 378 of file YouBotJoint.cpp.
|
protectedvirtual |
Implements youbot::Joint.
Definition at line 435 of file YouBotJoint.cpp.
|
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 506 of file YouBotJoint.cpp.
|
virtual |
gets the velocity of one joint
data | returns the velocity by reference |
Definition at line 561 of file YouBotJoint.cpp.
|
virtual |
gets the velocity in round per minute of one joint
data | returns the velocity by reference |
Definition at line 586 of file YouBotJoint.cpp.
|
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 629 of file YouBotJoint.cpp.
|
virtual |
gets the encoder ticks of one joint
data | returns the ticks by reference |
Definition at line 672 of file YouBotJoint.cpp.
|
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 714 of file YouBotJoint.cpp.
|
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 749 of file YouBotJoint.cpp.
|
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 767 of file YouBotJoint.cpp.
|
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 794 of file YouBotJoint.cpp.
|
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 819 of file YouBotJoint.cpp.
|
virtual |
gets the ramp generator velocity of one joint (only firmware 2.0 or higher)
data | returns the velocity by reference |
Definition at line 840 of file YouBotJoint.cpp.
unsigned int youbot::YouBotJoint::getJointNumber | ( | ) |
Definition at line 1075 of file YouBotJoint.cpp.
|
virtual |
Returns the status messages for the motor controller.
Definition at line 908 of file YouBotJoint.cpp.
|
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 1011 of file YouBotJoint.cpp.
void youbot::YouBotJoint::getUserVariable | ( | const unsigned int | index, |
int & | data | ||
) |
Definition at line 863 of file YouBotJoint.cpp.
void youbot::YouBotJoint::noMoreAction | ( | ) |
Definition at line 1047 of file YouBotJoint.cpp.
|
private |
|
private |
Definition at line 1177 of file YouBotJoint.cpp.
|
private |
Definition at line 1081 of file YouBotJoint.cpp.
void youbot::YouBotJoint::restoreConfigurationParameter | ( | YouBotJointParameter & | parameter | ) |
Restores the joint parameter from the EEPROM.
Definition at line 411 of file YouBotJoint.cpp.
|
private |
Definition at line 1213 of file YouBotJoint.cpp.
|
protectedvirtual |
Implements youbot::Joint.
Definition at line 77 of file YouBotJoint.cpp.
|
virtual |
Definition at line 128 of file YouBotJoint.cpp.
|
virtual |
Definition at line 151 of file YouBotJoint.cpp.
|
virtual |
Definition at line 163 of file YouBotJoint.cpp.
|
virtual |
Definition at line 178 of file YouBotJoint.cpp.
|
virtual |
Definition at line 187 of file YouBotJoint.cpp.
|
virtual |
Definition at line 245 of file YouBotJoint.cpp.
|
virtual |
Definition at line 257 of file YouBotJoint.cpp.
|
virtual |
commutation method for firmware 1.48 and below
Definition at line 296 of file YouBotJoint.cpp.
|
virtual |
this method should be only used if you know what you are doing
Definition at line 360 of file YouBotJoint.cpp.
|
virtual |
Definition at line 384 of file YouBotJoint.cpp.
|
protectedvirtual |
Implements youbot::Joint.
Definition at line 429 of file YouBotJoint.cpp.
|
virtual |
commands a position or angle to one joint
data | the to command position |
Definition at line 443 of file YouBotJoint.cpp.
|
virtual |
commands a encoder value (position) to one joint
data | the to command encoder value |
Definition at line 479 of file YouBotJoint.cpp.
|
virtual |
commands a velocity to one joint
data | the to command velocity |
Definition at line 533 of file YouBotJoint.cpp.
|
virtual |
sets the velocity in round per minute to one joint
data | the setpoint velocity |
Definition at line 606 of file YouBotJoint.cpp.
|
virtual |
commands a current to one joint
data | the to command current |
Definition at line 650 of file YouBotJoint.cpp.
|
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 695 of file YouBotJoint.cpp.
|
virtual |
commands a torque to one joint
data | the to command torque |
Definition at line 730 of file YouBotJoint.cpp.
void youbot::YouBotJoint::setEncoderToZero | ( | ) |
set the encoder values of the joint to zero. This postion will be the new reference.
Definition at line 1021 of file YouBotJoint.cpp.
void youbot::YouBotJoint::setUserVariable | ( | const unsigned int | index, |
const int | data | ||
) |
Definition at line 886 of file YouBotJoint.cpp.
|
private |
Definition at line 1250 of file YouBotJoint.cpp.
void youbot::YouBotJoint::stopJoint | ( | ) |
Definition at line 1061 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 392 of file YouBotJoint.cpp.
|
private |
Definition at line 284 of file YouBotJoint.hpp.
|
private |
Definition at line 298 of file YouBotJoint.hpp.
|
private |
Definition at line 296 of file YouBotJoint.hpp.
|
private |
Definition at line 300 of file YouBotJoint.hpp.
|
private |
Definition at line 290 of file YouBotJoint.hpp.
|
private |
Definition at line 294 of file YouBotJoint.hpp.
|
private |
Definition at line 286 of file YouBotJoint.hpp.
|
private |
Definition at line 292 of file YouBotJoint.hpp.
|
private |
Definition at line 288 of file YouBotJoint.hpp.
JointTrajectoryController youbot::YouBotJoint::trajectoryController |
Definition at line 280 of file YouBotJoint.hpp.