1 #ifndef YOUBOT_YOUBOTMANIPULATOR_H 2 #define YOUBOT_YOUBOTMANIPULATOR_H 61 #include <boost/ptr_container/ptr_vector.hpp> 62 #include <boost/scoped_ptr.hpp> 70 YouBotManipulator(
const std::string name,
const std::string configFilePath =
"../config/");
100 virtual void getJointData(std::vector<JointSensedAngle>& data);
105 virtual void setJointData(
const std::vector<JointVelocitySetpoint>& JointData);
110 virtual void getJointData(std::vector<JointSensedVelocity>& data);
115 virtual void setJointData(
const std::vector<JointCurrentSetpoint>& JointData);
120 virtual void getJointData(std::vector<JointSensedCurrent>& data);
125 virtual void setJointData(
const std::vector<JointTorqueSetpoint>& JointData);
130 virtual void getJointData(std::vector<JointSensedTorque>& data);
YouBotGripper & getArmGripper()
void doJointCommutation()
does the sine commutation of the arm joints
It groups the manipulator joints and the gripper together.
YouBotManipulator(const std::string name, const std::string configFilePath="../config/")
virtual ~YouBotManipulator()
EthercatMasterWithThread * ethercatMasterWithThread
std::string actualFirmwareVersionAllJoints
The youBot gripper with one degree of freedom.
void calibrateManipulator(const bool forceCalibration=false)
calibrate the reference position of the arm joints
boost::ptr_vector< YouBotJoint > joints
boost::scoped_ptr< ConfigFile > configfile
The number of manipulator joints.
virtual void setJointData(const std::vector< JointAngleSetpoint > &JointData)
int getNumberJoints()
return the number of joints
std::vector< std::string > supportedFirmwareVersions
YouBotManipulator & operator=(const YouBotManipulator &source)
YouBotJoint & getArmJoint(const unsigned int armJointNumber)
virtual void getJointData(std::vector< JointSensedAngle > &data)
The Ethercat Master interface.
boost::scoped_ptr< YouBotGripper > gripper
void commutationFirmware200()
does the commutation of the arm joints with firmware 2.0
void calibrateGripper(const bool forceCalibration=false)
void commutationFirmware148()
does the commutation of the arm joints with firmware 1.48 and below
EthercatMasterInterface & ethercatMaster
int alternativeControllerType
abstract data class for joints
unsigned int numberArmJoints
bool isGripperInitialized