1 #ifndef YOUBOT_YOUBOTJOINT_H 2 #define YOUBOT_YOUBOTJOINT_H 57 #include <boost/thread.hpp> 58 #include <boost/scoped_ptr.hpp> 79 YouBotJoint(
const unsigned int jointNo,
const std::string& configFilePath =
"../config/");
236 virtual void getStatus(std::vector<std::string>& statusMessages);
257 virtual void getStatus(
unsigned int& statusFlags);
EthercatMasterInterface * ethercatMaster
the firmware version of the joint
void parseMailboxStatusFlags(const YouBotSlaveMailboxMsg &mailboxMsg)
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
virtual void getConfigurationParameter(JointParameter ¶meter)
the resolution of the encoders, it is needed for the calculations of the youBot Driver ...
bool retrieveValueFromMotorContoller(YouBotSlaveMailboxMsg &message)
YouBotSlaveMsg messageBuffer
Sensed encoder ticks of the joint.
unsigned int mailboxMsgRetries
Set-point velocity of the joint.
The torque set-point of the joint will be set by setting the computed current set-point.
JointTrajectoryController trajectoryController
quantity< si::angular_velocity > lastVelocity
Output part from the EtherCat message of the youBot EtherCat slaves.
virtual void setData(const JointDataSetpoint &data)
joint position limits in encoder ticks
void getUserVariable(const unsigned int index, int &data)
virtual void setConfigurationParameter(const JointParameter ¶meter)
void parseYouBotErrorFlags(const YouBotSlaveMsg &messageBuffer)
This torque of the joint is computed from the actual current.
void storeConfigurationParameterPermanent(const YouBotJointParameter ¶meter)
joint position limits in radian
Sensed velocity of the joint.
unsigned int getJointNumber()
bool positionReferenceToZero
unsigned int timeTillNextMailboxUpdate
Sensed rounds per minute (rpm) of the joint.
the gear ratio which is needed for the calculations in the youBot driver
Sensed electric current of the joint.
encoder ticks setpoint of the joint
YouBotJointStorage storage
EtherCAT mailbox message of the youBot slaves.
abstract youBot joint parameter
inverse the joint movement direction
The Ethercat Master interface.
void setUserVariable(const unsigned int index, const int data)
YouBotJoint & operator=(const YouBotJoint &source)
bool setValueToMotorContoller(const YouBotSlaveMailboxMsg &mailboxMsg)
quantity< plane_angle > lastPosition
virtual void getStatus(std::vector< std::string > &statusMessages)
Returns the status messages for the motor controller.
abstract data class for commanded joint data
void restoreConfigurationParameter(YouBotJointParameter ¶meter)
Restores the joint parameter from the EEPROM.
Set-point current of the joint.
boost::scoped_ptr< JointLimitMonitor > limitMonitor
abstract youBot joint parameter which can be read only
virtual void getData(JointData &data)
Joint Trajectory Controller.
void setEncoderToZero()
set the encoder values of the joint to zero. This postion will be the new reference.
Stores YouBotJoint informations which are needed in the driver.
abstract data class for joints
EtherCat message of the youBot EtherCat slaves.
Sensed position / angle of the joint.
YouBotJoint(const unsigned int jointNo, const std::string &configFilePath="../config/")
Set-point angle / position of the joint.
Rounds per minute set-point of the joint.
Sensed velocity of the joint.