Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
PowerCubeSim Class Reference

#include <PowerCubeSim.h>

Public Types

enum  PC_CTRL_STATE { PC_CTRL_OK = 0, PC_CTRL_NOT_REFERENCED = -1, PC_CTRL_ERR = -2, PC_CTRL_POW_VOLT_ERR = -3 }
 Looks for connected Modules and returns their Ids in a vector. More...
 

Public Member Functions

int Close ()
 
bool getConfig (std::vector< double > &result)
 Returns the current Joint Angles. More...
 
std::vector< double > getCurrentAngularMaxAccel ()
 
std::vector< double > getCurrentAngularMaxVel ()
 
std::string getErrorMessage () const
 
bool getJointVelocities (std::vector< double > &result)
 Returns the current Angular velocities (Rad/s) More...
 
vector< int > getModuleMap () const
 
bool getStatusMoving (int cubeNo) const
 
bool Init (PowerCubeCtrlParams *params)
 
bool isInitialized () const
 
void millisleep (unsigned int milliseconds) const
 
bool MoveJointSpaceSync (const std::vector< double > &Angle)
 same as MoveJointSpace, but final angles should by reached simultaniously! Returns the time that the movement will take More...
 
bool MoveVel (const std::vector< double > &vel)
 Moves all cubes by the given velocities. More...
 
 PowerCubeSim ()
 
void setCurrentAngles (std::vector< double > Angles)
 
void setCurrentJointVelocities (std::vector< double > Angles)
 
bool setMaxAcceleration (double radPerSecSquared)
 Sets the maximum angular acceleration (rad/s^2) for the Joints, use with care! A Value of 0.5 is already pretty fast, you probably don't want anything more than one... More...
 
bool setMaxAcceleration (const std::vector< double > &radPerSecSquared)
 
bool setMaxVelocity (double radpersec)
 Sets the maximum angular velocity (rad/s) for the Joints, use with care! A Value of 0.5 is already pretty fast, you probably don't want anything more than one... More...
 
bool setMaxVelocity (const std::vector< double > &radpersec)
 
void setStatusMoving (int cubeNo, bool moving)
 
bool statusAcc ()
 Returs true if any of the Joints are accelerating. More...
 
bool statusDec ()
 Returns true if any of the Joints are decelerating. More...
 
bool statusMoving ()
 Returns true if any of the Joints are still moving Should also return true if Joints are accelerating or decelerating. More...
 
bool statusMoving (int cubeNo)
 
bool Stop ()
 Stops the Manipulator immediately. More...
 
 ~PowerCubeSim ()
 

Public Attributes

double maxVel
 

Protected Member Functions

int startSimulatedMovement (std::vector< double > target)
 
double timeRampMove (double dtheta, double vnow, double v, double a)
 Tells the Modules not to start moving until PCubel_startMotionAll is called. More...
 

Protected Attributes

Jointd m_AngleOffsets
 
pthread_mutex_t m_Angles_Mutex
 
pthread_mutex_t m_AngularVel_Mutex
 
std::vector< double > m_CurrentAngles
 
std::vector< double > m_CurrentAngularMaxAccel
 
std::vector< double > m_CurrentAngularMaxVel
 
std::vector< double > m_CurrentAngularVel
 
int m_Dev
 
int m_DOF
 
std::string m_ErrorMessage
 
vector< int > m_IdModules
 
int m_Initialized
 
std::vector< double > m_maxAcc
 
std::vector< double > m_maxVel
 
pthread_mutex_t m_Movement_Mutex
 
std::vector< bool > m_MovementInProgress
 
int m_NumOfModules
 
SimThreadArgs ** m_SimThreadArgs
 
pthread_t * m_SimThreadID
 
float maxAcc
 

Detailed Description

Definition at line 62 of file PowerCubeSim.h.

Member Enumeration Documentation

Looks for connected Modules and returns their Ids in a vector.

Waits until all Modules are homed, writes status comments to out.

Enumerator
PC_CTRL_OK 
PC_CTRL_NOT_REFERENCED 
PC_CTRL_ERR 
PC_CTRL_POW_VOLT_ERR 

Definition at line 142 of file PowerCubeSim.h.

Constructor & Destructor Documentation

PowerCubeSim::PowerCubeSim ( )

Definition at line 42 of file PowerCubeSim.cpp.

PowerCubeSim::~PowerCubeSim ( )

The Deconstructor

Definition at line 124 of file PowerCubeSim.cpp.

Member Function Documentation

int PowerCubeSim::Close ( )
inline

Definition at line 80 of file PowerCubeSim.h.

bool PowerCubeSim::getConfig ( std::vector< double > &  result)

Returns the current Joint Angles.

Definition at line 135 of file PowerCubeSim.cpp.

std::vector<double> PowerCubeSim::getCurrentAngularMaxAccel ( )
inline

Definition at line 166 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::getCurrentAngularMaxVel ( )
inline

Definition at line 162 of file PowerCubeSim.h.

std::string PowerCubeSim::getErrorMessage ( ) const
inline

Definition at line 75 of file PowerCubeSim.h.

bool PowerCubeSim::getJointVelocities ( std::vector< double > &  result)

Returns the current Angular velocities (Rad/s)

Definition at line 156 of file PowerCubeSim.cpp.

vector<int> PowerCubeSim::getModuleMap ( ) const
inline

Definition at line 158 of file PowerCubeSim.h.

bool PowerCubeSim::getStatusMoving ( int  cubeNo) const
inline

Definition at line 153 of file PowerCubeSim.h.

bool PowerCubeSim::Init ( PowerCubeCtrlParams params)

The Init function opens the bus and initializes it. Furthermore the Id`s of the Cubes are taken and mapped. These function has to be used before the cubes can be positioned after the power up.

Parameters
m_DOFgives the number of Degrees of freedom of the manipulator which is connected (the gripper is not counted as DOF)

Definition at line 58 of file PowerCubeSim.cpp.

bool PowerCubeSim::isInitialized ( ) const
inline

Definition at line 70 of file PowerCubeSim.h.

void PowerCubeSim::millisleep ( unsigned int  milliseconds) const

Definition at line 672 of file PowerCubeSim.cpp.

bool PowerCubeSim::MoveJointSpaceSync ( const std::vector< double > &  Angle)

same as MoveJointSpace, but final angles should by reached simultaniously! Returns the time that the movement will take

same as MoveJointSpace, but final angles should by reached simultaniously!

Definition at line 205 of file PowerCubeSim.cpp.

bool PowerCubeSim::MoveVel ( const std::vector< double > &  vel)

Moves all cubes by the given velocities.

Starts moving all cubes with the given velocities.

Definition at line 338 of file PowerCubeSim.cpp.

void PowerCubeSim::setCurrentAngles ( std::vector< double >  Angles)

Definition at line 174 of file PowerCubeSim.cpp.

void PowerCubeSim::setCurrentJointVelocities ( std::vector< double >  Angles)

Definition at line 189 of file PowerCubeSim.cpp.

bool PowerCubeSim::setMaxAcceleration ( double  radPerSecSquared)

Sets the maximum angular acceleration (rad/s^2) for the Joints, use with care! A Value of 0.5 is already pretty fast, you probably don't want anything more than one...

Definition at line 385 of file PowerCubeSim.cpp.

bool PowerCubeSim::setMaxAcceleration ( const std::vector< double > &  radPerSecSquared)

Definition at line 396 of file PowerCubeSim.cpp.

bool PowerCubeSim::setMaxVelocity ( double  radpersec)

Sets the maximum angular velocity (rad/s) for the Joints, use with care! A Value of 0.5 is already pretty fast, you probably don't want anything more than one...

Definition at line 365 of file PowerCubeSim.cpp.

bool PowerCubeSim::setMaxVelocity ( const std::vector< double > &  radpersec)

Definition at line 374 of file PowerCubeSim.cpp.

void PowerCubeSim::setStatusMoving ( int  cubeNo,
bool  moving 
)

Definition at line 455 of file PowerCubeSim.cpp.

int PowerCubeSim::startSimulatedMovement ( std::vector< double >  target)
protected

Definition at line 652 of file PowerCubeSim.cpp.

bool PowerCubeSim::statusAcc ( )

Returs true if any of the Joints are accelerating.

Definition at line 485 of file PowerCubeSim.cpp.

bool PowerCubeSim::statusDec ( )

Returns true if any of the Joints are decelerating.

Definition at line 469 of file PowerCubeSim.cpp.

bool PowerCubeSim::statusMoving ( )

Returns true if any of the Joints are still moving Should also return true if Joints are accelerating or decelerating.

Returns true if some cubes are still moving.

Definition at line 409 of file PowerCubeSim.cpp.

bool PowerCubeSim::statusMoving ( int  cubeNo)

Definition at line 434 of file PowerCubeSim.cpp.

bool PowerCubeSim::Stop ( )

Stops the Manipulator immediately.

Definition at line 356 of file PowerCubeSim.cpp.

double PowerCubeSim::timeRampMove ( double  dtheta,
double  vnow,
double  v,
double  a 
)
protected

Tells the Modules not to start moving until PCubel_startMotionAll is called.

Returns the time for a ramp-move about dtheta with v, a would take, assuming the module is currently moving at vnowClose.

Execute move commands immediately from now on: Returns the time for a ramp-move about dtheta with v, a would take, assuming the module is currently moving at vnowClose

Definition at line 296 of file PowerCubeSim.cpp.

Member Data Documentation

Jointd PowerCubeSim::m_AngleOffsets
protected

Definition at line 198 of file PowerCubeSim.h.

pthread_mutex_t PowerCubeSim::m_Angles_Mutex
protected

Definition at line 213 of file PowerCubeSim.h.

pthread_mutex_t PowerCubeSim::m_AngularVel_Mutex
protected

Definition at line 214 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::m_CurrentAngles
protected

Definition at line 202 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::m_CurrentAngularMaxAccel
protected

Definition at line 205 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::m_CurrentAngularMaxVel
protected

Definition at line 204 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::m_CurrentAngularVel
protected

Definition at line 203 of file PowerCubeSim.h.

int PowerCubeSim::m_Dev
protected

Definition at line 192 of file PowerCubeSim.h.

int PowerCubeSim::m_DOF
protected

Definition at line 189 of file PowerCubeSim.h.

std::string PowerCubeSim::m_ErrorMessage
protected

Definition at line 209 of file PowerCubeSim.h.

vector<int> PowerCubeSim::m_IdModules
protected

Definition at line 193 of file PowerCubeSim.h.

int PowerCubeSim::m_Initialized
protected

Definition at line 190 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::m_maxAcc
protected

Definition at line 196 of file PowerCubeSim.h.

std::vector<double> PowerCubeSim::m_maxVel
protected

Definition at line 195 of file PowerCubeSim.h.

pthread_mutex_t PowerCubeSim::m_Movement_Mutex
protected

Definition at line 215 of file PowerCubeSim.h.

std::vector<bool> PowerCubeSim::m_MovementInProgress
protected

Definition at line 200 of file PowerCubeSim.h.

int PowerCubeSim::m_NumOfModules
protected

Definition at line 191 of file PowerCubeSim.h.

SimThreadArgs** PowerCubeSim::m_SimThreadArgs
protected

Definition at line 217 of file PowerCubeSim.h.

pthread_t* PowerCubeSim::m_SimThreadID
protected

Definition at line 216 of file PowerCubeSim.h.

float PowerCubeSim::maxAcc
protected

Definition at line 211 of file PowerCubeSim.h.

double PowerCubeSim::maxVel

Definition at line 150 of file PowerCubeSim.h.


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


schunk_powercube_chain
Author(s): Florian Weisshardt
autogenerated on Mon Nov 25 2019 03:48:21