#include <YouBotBase.hpp>
Public Member Functions | |
void | doJointCommutation () |
does the sine commutation of the base joints | |
YouBotJoint & | getBaseJoint (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) | |
virtual | ~YouBotBase () |
Public Attributes | |
FourSwedishWheelOmniBaseKinematic | youBotBaseKinematic |
This class represents the kinematic of the YouBot. | |
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 () |
void | initializeKinematic () |
YouBotBase & | operator= (const YouBotBase &source) |
YouBotBase (const YouBotBase &source) | |
Private Attributes | |
std::string | actualFirmwareVersionAllJoints |
int | alternativeControllerType |
boost::scoped_ptr< ConfigFile > | configfile |
int | controllerType |
EthercatMasterInterface & | ethercatMaster |
EthercatMasterWithThread * | ethercatMasterWithThread |
boost::ptr_vector< YouBotJoint > | joints |
std::vector< std::string > | supportedFirmwareVersions |
It groups the base joints together
Definition at line 80 of file YouBotBase.hpp.
youbot::YouBotBase::YouBotBase | ( | const std::string | name, |
const std::string | configFilePath | ||
) |
Definition at line 55 of file YouBotBase.cpp.
youbot::YouBotBase::~YouBotBase | ( | ) | [virtual] |
Definition at line 90 of file YouBotBase.cpp.
youbot::YouBotBase::YouBotBase | ( | const YouBotBase & | source | ) | [private] |
void youbot::YouBotBase::commutationFirmware148 | ( | ) | [private] |
does the commutation of the arm joints with firmware 1.48 and below
Definition at line 512 of file YouBotBase.cpp.
void youbot::YouBotBase::commutationFirmware200 | ( | ) | [private] |
does the commutation of the arm joints with firmware 2.0
Definition at line 417 of file YouBotBase.cpp.
does the sine commutation of the base joints
Definition at line 104 of file YouBotBase.cpp.
YouBotJoint & youbot::YouBotBase::getBaseJoint | ( | const unsigned int | baseJointNumber | ) |
return a joint form the base
baseJointNumber | 1-4 for the base joints |
Definition at line 125 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
longitudinalPosition | is the forward or backward position |
transversalPosition | is the sideway position |
orientation | is the rotation around the center of the YouBot |
Definition at line 140 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
longitudinalVelocity | is the forward or backward velocity |
transversalVelocity | is the sideway velocity |
angularVelocity | is the rotational velocity around the center of the YouBot |
Definition at line 219 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
data | returns the angles by reference |
Definition at line 301 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
data | returns the velocities by reference |
Definition at line 335 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
data | returns the actual motor currents by reference |
Definition at line 369 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
data | returns the actual joint torque by reference |
Definition at line 403 of file YouBotBase.cpp.
void youbot::YouBotBase::initializeJoints | ( | ) | [private] |
Definition at line 598 of file YouBotBase.cpp.
void youbot::YouBotBase::initializeKinematic | ( | ) | [private] |
Definition at line 779 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
longitudinalPosition | is the forward or backward position |
transversalPosition | is the sideway position |
orientation | is the rotation around the center of the YouBot |
Definition at line 170 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
longitudinalVelocity | is the forward or backward velocity |
transversalVelocity | is the sideway velocity |
angularVelocity | is the rotational velocity around the center of the YouBot |
Definition at line 251 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
JointData | the to command positions |
Definition at line 282 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
JointData | the to command velocities |
Definition at line 317 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
JointData | the to command current |
Definition at line 351 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
JointData | the to command torque |
Definition at line 385 of file YouBotBase.cpp.
std::string youbot::YouBotBase::actualFirmwareVersionAllJoints [private] |
Definition at line 195 of file YouBotBase.hpp.
int youbot::YouBotBase::alternativeControllerType [private] |
Definition at line 187 of file YouBotBase.hpp.
boost::scoped_ptr<ConfigFile> youbot::YouBotBase::configfile [private] |
Definition at line 181 of file YouBotBase.hpp.
int youbot::YouBotBase::controllerType [private] |
Definition at line 185 of file YouBotBase.hpp.
Definition at line 189 of file YouBotBase.hpp.
Definition at line 191 of file YouBotBase.hpp.
boost::ptr_vector<YouBotJoint> youbot::YouBotBase::joints [private] |
Definition at line 183 of file YouBotBase.hpp.
std::vector<std::string> youbot::YouBotBase::supportedFirmwareVersions [private] |
Definition at line 193 of file YouBotBase.hpp.
This class represents the kinematic of the YouBot.
Definition at line 124 of file YouBotBase.hpp.