Public Member Functions | Private Member Functions | Private Attributes | List of all members
youbot::YouBotManipulator Class Reference

It groups the manipulator joints and the gripper together. More...

#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 More...
 
void doJointCommutation ()
 does the sine commutation of the arm joints More...
 
YouBotGrippergetArmGripper ()
 
YouBotJointgetArmJoint (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)
 
int getNumberJoints ()
 return the number of joints More...
 
bool hasGripper ()
 
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="../config/")
 
virtual ~YouBotManipulator ()
 

Private Member Functions

void commutationFirmware148 ()
 does the commutation of the arm joints with firmware 1.48 and below More...
 
void commutationFirmware200 ()
 does the commutation of the arm joints with firmware 2.0 More...
 
void initializeJoints ()
 
YouBotManipulatoroperator= (const YouBotManipulator &source)
 
 YouBotManipulator (const YouBotManipulator &source)
 

Private Attributes

std::string actualFirmwareVersionAllJoints
 
int alternativeControllerType
 
boost::scoped_ptr< ConfigFileconfigfile
 The number of manipulator joints. More...
 
int controllerType
 
EthercatMasterInterfaceethercatMaster
 
EthercatMasterWithThreadethercatMasterWithThread
 
boost::scoped_ptr< YouBotGrippergripper
 
bool isGripperInitialized
 
boost::ptr_vector< YouBotJointjoints
 
unsigned int numberArmJoints
 
std::vector< std::string > supportedFirmwareVersions
 
bool useGripper
 

Detailed Description

It groups the manipulator joints and the gripper together.

Definition at line 68 of file YouBotManipulator.hpp.

Constructor & Destructor Documentation

youbot::YouBotManipulator::YouBotManipulator ( const std::string  name,
const std::string  configFilePath = "../config/" 
)

Definition at line 56 of file YouBotManipulator.cpp.

youbot::YouBotManipulator::~YouBotManipulator ( )
virtual

Definition at line 87 of file YouBotManipulator.cpp.

youbot::YouBotManipulator::YouBotManipulator ( const YouBotManipulator source)
private

Member Function Documentation

void youbot::YouBotManipulator::calibrateGripper ( const bool  forceCalibration = false)

Definition at line 279 of file YouBotManipulator.cpp.

void youbot::YouBotManipulator::calibrateManipulator ( const bool  forceCalibration = false)

calibrate the reference position of the arm joints

Definition at line 112 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 517 of file YouBotManipulator.cpp.

void youbot::YouBotManipulator::commutationFirmware200 ( )
private

does the commutation of the arm joints with firmware 2.0

Definition at line 436 of file YouBotManipulator.cpp.

void youbot::YouBotManipulator::doJointCommutation ( )

does the sine commutation of the arm joints

Definition at line 98 of file YouBotManipulator.cpp.

YouBotGripper & youbot::YouBotManipulator::getArmGripper ( )

Definition at line 313 of file YouBotManipulator.cpp.

YouBotJoint & youbot::YouBotManipulator::getArmJoint ( const unsigned int  armJointNumber)

return a joint form the arm1

Parameters
armJointNumber1-5 for the arm joints

Definition at line 303 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

Parameters
datareturns the angles by reference

Definition at line 341 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

Parameters
datareturns the velocities by reference

Definition at line 369 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

Parameters
datareturns the actual motor currents by reference

Definition at line 397 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

Parameters
datareturns the actual joint torque by reference

Definition at line 425 of file YouBotManipulator.cpp.

int youbot::YouBotManipulator::getNumberJoints ( )

return the number of joints

Definition at line 293 of file YouBotManipulator.cpp.

bool youbot::YouBotManipulator::hasGripper ( )

Definition at line 297 of file YouBotManipulator.cpp.

void youbot::YouBotManipulator::initializeJoints ( )
private

Definition at line 591 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

Parameters
JointDatathe to command positions

Definition at line 325 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

Parameters
JointDatathe to command velocities

Definition at line 354 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

Parameters
JointDatathe to command current

Definition at line 382 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

Parameters
JointDatathe to command torque

Definition at line 410 of file YouBotManipulator.cpp.

Member Data Documentation

std::string youbot::YouBotManipulator::actualFirmwareVersionAllJoints
private

Definition at line 167 of file YouBotManipulator.hpp.

int youbot::YouBotManipulator::alternativeControllerType
private

Definition at line 163 of file YouBotManipulator.hpp.

boost::scoped_ptr<ConfigFile> youbot::YouBotManipulator::configfile
private

The number of manipulator joints.

Definition at line 148 of file YouBotManipulator.hpp.

int youbot::YouBotManipulator::controllerType
private

Definition at line 154 of file YouBotManipulator.hpp.

EthercatMasterInterface& youbot::YouBotManipulator::ethercatMaster
private

Definition at line 156 of file YouBotManipulator.hpp.

EthercatMasterWithThread* youbot::YouBotManipulator::ethercatMasterWithThread
private

Definition at line 161 of file YouBotManipulator.hpp.

boost::scoped_ptr<YouBotGripper> youbot::YouBotManipulator::gripper
private

Definition at line 152 of file YouBotManipulator.hpp.

bool youbot::YouBotManipulator::isGripperInitialized
private

Definition at line 159 of file YouBotManipulator.hpp.

boost::ptr_vector<YouBotJoint> youbot::YouBotManipulator::joints
private

Definition at line 150 of file YouBotManipulator.hpp.

unsigned int youbot::YouBotManipulator::numberArmJoints
private

Definition at line 146 of file YouBotManipulator.hpp.

std::vector<std::string> youbot::YouBotManipulator::supportedFirmwareVersions
private

Definition at line 165 of file YouBotManipulator.hpp.

bool youbot::YouBotManipulator::useGripper
private

Definition at line 158 of file YouBotManipulator.hpp.


The documentation for this class was generated from the following files:


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:27