#include <YouBotManipulator.hpp>
Public Member Functions | |
void | calibrateGripper (const bool forceCalibration=false) |
void | calibrateManipulator (const bool forceCalibration=false) |
calibrate the reference position of the arm joints | |
void | doJointCommutation () |
does the sine commutation of the arm joints | |
YouBotGripper & | getArmGripper () |
YouBotJoint & | getArmJoint (const unsigned int armJointNumber) |
virtual void | getJointData (std::vector< JointSensedAngle > &data) |
virtual void | getJointData (std::vector< JointSensedVelocity > &data) |
virtual void | getJointData (std::vector< JointSensedCurrent > &data) |
virtual void | getJointData (std::vector< JointSensedTorque > &data) |
bool | isEtherCATConnectionEstablished () |
virtual void | setJointData (const std::vector< JointAngleSetpoint > &JointData) |
virtual void | setJointData (const std::vector< JointVelocitySetpoint > &JointData) |
virtual void | setJointData (const std::vector< JointCurrentSetpoint > &JointData) |
virtual void | setJointData (const std::vector< JointTorqueSetpoint > &JointData) |
YouBotManipulator (const std::string name, const std::string configFilePath) | |
virtual | ~YouBotManipulator () |
Private Member Functions | |
void | commutationFirmware148 () |
does the commutation of the arm joints with firmware 1.48 and below | |
void | commutationFirmware200 () |
does the commutation of the arm joints with firmware 2.0 | |
void | initializeJoints () |
YouBotManipulator & | operator= (const YouBotManipulator &source) |
YouBotManipulator (const YouBotManipulator &source) | |
Private Attributes | |
std::string | actualFirmwareVersionAllJoints |
int | alternativeControllerType |
boost::scoped_ptr< ConfigFile > | configfile |
int | controllerType |
EthercatMasterInterface & | ethercatMaster |
EthercatMasterWithThread * | ethercatMasterWithThread |
boost::scoped_ptr< YouBotGripper > | gripper |
boost::ptr_vector< YouBotJoint > | joints |
std::vector< std::string > | supportedFirmwareVersions |
bool | useGripper |
It groups the manipulator joints and the gripper together
Definition at line 78 of file YouBotManipulator.hpp.
youbot::YouBotManipulator::YouBotManipulator | ( | const std::string | name, |
const std::string | configFilePath | ||
) |
Definition at line 55 of file YouBotManipulator.cpp.
youbot::YouBotManipulator::~YouBotManipulator | ( | ) | [virtual] |
Definition at line 88 of file YouBotManipulator.cpp.
youbot::YouBotManipulator::YouBotManipulator | ( | const YouBotManipulator & | source | ) | [private] |
void youbot::YouBotManipulator::calibrateGripper | ( | const bool | forceCalibration = false | ) |
Definition at line 305 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::calibrateManipulator | ( | const bool | forceCalibration = false | ) |
calibrate the reference position of the arm joints
Definition at line 122 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::commutationFirmware148 | ( | ) | [private] |
does the commutation of the arm joints with firmware 1.48 and below
Definition at line 586 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::commutationFirmware200 | ( | ) | [private] |
does the commutation of the arm joints with firmware 2.0
Definition at line 491 of file YouBotManipulator.cpp.
does the sine commutation of the arm joints
Definition at line 102 of file YouBotManipulator.cpp.
Definition at line 334 of file YouBotManipulator.cpp.
YouBotJoint & youbot::YouBotManipulator::getArmJoint | ( | const unsigned int | armJointNumber | ) |
return a joint form the arm1
armJointNumber | 1-5 for the arm joints |
Definition at line 322 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::getJointData | ( | std::vector< JointSensedAngle > & | data | ) | [virtual] |
gets the position or angle of all manipulator joints which have been calculated from the actual encoder value These values are all read at the same time from the different joints
data | returns the angles by reference |
Definition at line 368 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::getJointData | ( | std::vector< JointSensedVelocity > & | data | ) | [virtual] |
gets the velocities of all manipulator joints which have been calculated from the actual encoder values These values are all read at the same time from the different joints
data | returns the velocities by reference |
Definition at line 404 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::getJointData | ( | std::vector< JointSensedCurrent > & | data | ) | [virtual] |
gets the motor currents of all manipulator joints which have been measured by a hal sensor These values are all read at the same time from the different joints
data | returns the actual motor currents by reference |
Definition at line 440 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::getJointData | ( | std::vector< JointSensedTorque > & | data | ) | [virtual] |
gets the joint torque of all manipulator joints which have been calculated from the current These values are all read at the same time from the different joints
data | returns the actual joint torque by reference |
Definition at line 476 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::initializeJoints | ( | ) | [private] |
Definition at line 673 of file YouBotManipulator.cpp.
Definition at line 928 of file YouBotManipulator.cpp.
YouBotManipulator& youbot::YouBotManipulator::operator= | ( | const YouBotManipulator & | source | ) | [private] |
void youbot::YouBotManipulator::setJointData | ( | const std::vector< JointAngleSetpoint > & | JointData | ) | [virtual] |
commands positions or angles to all manipulator joints all positions will be set at the same time
JointData | the to command positions |
Definition at line 348 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::setJointData | ( | const std::vector< JointVelocitySetpoint > & | JointData | ) | [virtual] |
commands velocities to all manipulator joints all velocities will be set at the same time
JointData | the to command velocities |
Definition at line 385 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::setJointData | ( | const std::vector< JointCurrentSetpoint > & | JointData | ) | [virtual] |
commands current to all manipulator joints all current values will be set at the same time
JointData | the to command current |
Definition at line 421 of file YouBotManipulator.cpp.
void youbot::YouBotManipulator::setJointData | ( | const std::vector< JointTorqueSetpoint > & | JointData | ) | [virtual] |
commands torque to all manipulator joints all torque values will be set at the same time
JointData | the to command torque |
Definition at line 457 of file YouBotManipulator.cpp.
std::string youbot::YouBotManipulator::actualFirmwareVersionAllJoints [private] |
Definition at line 173 of file YouBotManipulator.hpp.
int youbot::YouBotManipulator::alternativeControllerType [private] |
Definition at line 169 of file YouBotManipulator.hpp.
boost::scoped_ptr<ConfigFile> youbot::YouBotManipulator::configfile [private] |
Definition at line 155 of file YouBotManipulator.hpp.
int youbot::YouBotManipulator::controllerType [private] |
Definition at line 161 of file YouBotManipulator.hpp.
Definition at line 163 of file YouBotManipulator.hpp.
Definition at line 167 of file YouBotManipulator.hpp.
boost::scoped_ptr<YouBotGripper> youbot::YouBotManipulator::gripper [private] |
Definition at line 159 of file YouBotManipulator.hpp.
boost::ptr_vector<YouBotJoint> youbot::YouBotManipulator::joints [private] |
Definition at line 157 of file YouBotManipulator.hpp.
std::vector<std::string> youbot::YouBotManipulator::supportedFirmwareVersions [private] |
Definition at line 171 of file YouBotManipulator.hpp.
bool youbot::YouBotManipulator::useGripper [private] |
Definition at line 165 of file YouBotManipulator.hpp.