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

It groups the base joints together. More...

#include <YouBotBase.hpp>

Public Member Functions

void doJointCommutation ()
 does the sine commutation of the base joints More...
 
YouBotJointgetBaseJoint (const unsigned int baseJointNumber)
 
void getBasePosition (quantity< si::length > &longitudinalPosition, quantity< si::length > &transversalPosition, quantity< plane_angle > &orientation)
 
void getBaseVelocity (quantity< si::velocity > &longitudinalVelocity, quantity< si::velocity > &transversalVelocity, quantity< si::angular_velocity > &angularVelocity)
 
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)
 
void setBasePosition (const quantity< si::length > &longitudinalPosition, const quantity< si::length > &transversalPosition, const quantity< plane_angle > &orientation)
 
void setBaseVelocity (const quantity< si::velocity > &longitudinalVelocity, const quantity< si::velocity > &transversalVelocity, const quantity< si::angular_velocity > &angularVelocity)
 
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)
 
 YouBotBase (const std::string name, const std::string configFilePath="../config/")
 
virtual ~YouBotBase ()
 

Public Attributes

FourSwedishWheelOmniBaseKinematic youBotBaseKinematic
 This class represents the kinematic of the YouBot. More...
 

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 ()
 
void initializeKinematic ()
 
YouBotBaseoperator= (const YouBotBase &source)
 
 YouBotBase (const YouBotBase &source)
 

Private Attributes

std::string actualFirmwareVersionAllJoints
 
int alternativeControllerType
 
boost::scoped_ptr< ConfigFileconfigfile
 
int controllerType
 
EthercatMasterInterfaceethercatMaster
 
EthercatMasterWithThreadethercatMasterWithThread
 
boost::ptr_vector< YouBotJointjoints
 
std::vector< std::string > supportedFirmwareVersions
 

Detailed Description

It groups the base joints together.

Definition at line 76 of file YouBotBase.hpp.

Constructor & Destructor Documentation

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

Definition at line 55 of file YouBotBase.cpp.

youbot::YouBotBase::~YouBotBase ( )
virtual

Definition at line 84 of file YouBotBase.cpp.

youbot::YouBotBase::YouBotBase ( const YouBotBase source)
private

Member Function Documentation

void youbot::YouBotBase::commutationFirmware148 ( )
private

does the commutation of the arm joints with firmware 1.48 and below

Definition at line 461 of file YouBotBase.cpp.

void youbot::YouBotBase::commutationFirmware200 ( )
private

does the commutation of the arm joints with firmware 2.0

Definition at line 377 of file YouBotBase.cpp.

void youbot::YouBotBase::doJointCommutation ( )

does the sine commutation of the base joints

Definition at line 95 of file YouBotBase.cpp.

YouBotJoint & youbot::YouBotBase::getBaseJoint ( const unsigned int  baseJointNumber)

return a joint form the base

Parameters
baseJointNumber1-4 for the base joints

Definition at line 110 of file YouBotBase.cpp.

void youbot::YouBotBase::getBasePosition ( quantity< si::length > &  longitudinalPosition,
quantity< si::length > &  transversalPosition,
quantity< plane_angle > &  orientation 
)

gets the cartesien base position which is calculated from the odometry

Parameters
longitudinalPositionis the forward or backward position
transversalPositionis the sideway position
orientationis the rotation around the center of the YouBot

Definition at line 123 of file YouBotBase.cpp.

void youbot::YouBotBase::getBaseVelocity ( quantity< si::velocity > &  longitudinalVelocity,
quantity< si::velocity > &  transversalVelocity,
quantity< si::angular_velocity > &  angularVelocity 
)

gets the cartesien base velocity

Parameters
longitudinalVelocityis the forward or backward velocity
transversalVelocityis the sideway velocity
angularVelocityis the rotational velocity around the center of the YouBot

Definition at line 195 of file YouBotBase.cpp.

void youbot::YouBotBase::getJointData ( std::vector< JointSensedAngle > &  data)
virtual

gets the position or angle of all base 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 268 of file YouBotBase.cpp.

void youbot::YouBotBase::getJointData ( std::vector< JointSensedVelocity > &  data)
virtual

gets the velocities of all base 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 300 of file YouBotBase.cpp.

void youbot::YouBotBase::getJointData ( std::vector< JointSensedCurrent > &  data)
virtual

gets the motor currents of all base 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 332 of file YouBotBase.cpp.

void youbot::YouBotBase::getJointData ( std::vector< JointSensedTorque > &  data)
virtual

gets the joint torque of all base 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 364 of file YouBotBase.cpp.

void youbot::YouBotBase::initializeJoints ( )
private

Definition at line 537 of file YouBotBase.cpp.

void youbot::YouBotBase::initializeKinematic ( )
private

Definition at line 690 of file YouBotBase.cpp.

YouBotBase& youbot::YouBotBase::operator= ( const YouBotBase source)
private
void youbot::YouBotBase::setBasePosition ( const quantity< si::length > &  longitudinalPosition,
const quantity< si::length > &  transversalPosition,
const quantity< plane_angle > &  orientation 
)

sets the cartesien base position

Parameters
longitudinalPositionis the forward or backward position
transversalPositionis the sideway position
orientationis the rotation around the center of the YouBot

Definition at line 150 of file YouBotBase.cpp.

void youbot::YouBotBase::setBaseVelocity ( const quantity< si::velocity > &  longitudinalVelocity,
const quantity< si::velocity > &  transversalVelocity,
const quantity< si::angular_velocity > &  angularVelocity 
)

commands the base in cartesien velocities

Parameters
longitudinalVelocityis the forward or backward velocity
transversalVelocityis the sideway velocity
angularVelocityis the rotational velocity around the center of the YouBot

Definition at line 223 of file YouBotBase.cpp.

void youbot::YouBotBase::setJointData ( const std::vector< JointAngleSetpoint > &  JointData)
virtual

commands positions or angles to all base joints all positions will be set at the same time

Parameters
JointDatathe to command positions

Definition at line 250 of file YouBotBase.cpp.

void youbot::YouBotBase::setJointData ( const std::vector< JointVelocitySetpoint > &  JointData)
virtual

commands velocities to all base joints all velocities will be set at the same time

Parameters
JointDatathe to command velocities

Definition at line 283 of file YouBotBase.cpp.

void youbot::YouBotBase::setJointData ( const std::vector< JointCurrentSetpoint > &  JointData)
virtual

commands current to all base joints all current values will be set at the same time

Parameters
JointDatathe to command current

Definition at line 315 of file YouBotBase.cpp.

void youbot::YouBotBase::setJointData ( const std::vector< JointTorqueSetpoint > &  JointData)
virtual

commands torque to all base joints all torque values will be set at the same time

Parameters
JointDatathe to command torque

Definition at line 347 of file YouBotBase.cpp.

Member Data Documentation

std::string youbot::YouBotBase::actualFirmwareVersionAllJoints
private

Definition at line 186 of file YouBotBase.hpp.

int youbot::YouBotBase::alternativeControllerType
private

Definition at line 178 of file YouBotBase.hpp.

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

Definition at line 172 of file YouBotBase.hpp.

int youbot::YouBotBase::controllerType
private

Definition at line 176 of file YouBotBase.hpp.

EthercatMasterInterface& youbot::YouBotBase::ethercatMaster
private

Definition at line 180 of file YouBotBase.hpp.

EthercatMasterWithThread* youbot::YouBotBase::ethercatMasterWithThread
private

Definition at line 182 of file YouBotBase.hpp.

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

Definition at line 174 of file YouBotBase.hpp.

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

Definition at line 184 of file YouBotBase.hpp.

FourSwedishWheelOmniBaseKinematic youbot::YouBotBase::youBotBaseKinematic

This class represents the kinematic of the YouBot.

Definition at line 114 of file YouBotBase.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