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

#include <PowerCubeCtrl.h>

Public Types

enum  PC_CTRL_STATUS { PC_CTRL_OK = 0, PC_CTRL_NOT_HOMED = -1, PC_CTRL_ERR = -2, PC_CTRL_POW_VOLT_ERR = -3 }
 

Public Member Functions

bool Close ()
 Close. More...
 
bool doHoming ()
 Waits until all Modules are homed. More...
 
std::vector< double > getAccelerations ()
 Gets the current accelerations. More...
 
std::string getErrorMessage () const
 Get error message. More...
 
double getHorizon ()
 Gets the horizon (sec). More...
 
bool getJointAngles (std::vector< double > &result)
 get the current joint angles More...
 
bool getJointVelocities (std::vector< double > &result)
 get the current joint velocities (Rad/s) More...
 
PC_CTRL_STATUS getPC_Status () const
 Get PC_Status message. More...
 
std::vector< double > getPositions ()
 Gets the current positions. More...
 
bool getStatus (PC_CTRL_STATUS &status, std::vector< std::string > &errorMessages)
 Gets the status of the modules. More...
 
std::vector< double > getVelocities ()
 Gets the current velcities. More...
 
std::vector< unsigned long > getVersion ()
 Gets the firmware version of the modules. More...
 
bool Init (PowerCubeCtrlParams *params)
 Initializing. More...
 
bool isInitialized () const
 Checking if is initialized. More...
 
bool MoveJointSpaceSync (const std::vector< double > &angles)
 Send position goals to powercubes, the final angles will be reached simultaneously. More...
 
bool MoveVel (const std::vector< double > &velocities)
 Moves all cubes by the given velocities. More...
 
 PowerCubeCtrl (PowerCubeCtrlParams *params)
 Constructor. More...
 
bool Recover ()
 Recovery after emergency stop or power supply failure. More...
 
bool setASyncMotion ()
 Configure powercubes to start all movements asynchronously. More...
 
bool setHorizon (double horizon)
 Sets the horizon (sec). More...
 
bool setMaxAcceleration (double acceleration)
 Sets the maximum angular velocity (rad/s) for the Joints, use with care! More...
 
bool setMaxAcceleration (const std::vector< double > &accelerations)
 Sets the maximum angular acceleration (rad/s^2) for the Joints, use with care! More...
 
bool setMaxVelocity (double velocity)
 Sets the maximum angular velocity (rad/s) for the Joints, use with care! More...
 
bool setMaxVelocity (const std::vector< double > &velocities)
 Sets the maximum angular velocity (rad/s) for the Joints, use with care! More...
 
bool setSyncMotion ()
 Configure powercubes to start all movements synchronously. More...
 
bool statusMoving ()
 Returns true if any of the Joints are still moving. More...
 
bool Stop ()
 Stops the Manipulator immediately. More...
 
bool updateStates ()
 Returns the state of all modules. More...
 
void updateVelocities (std::vector< double > pos_temp, double delta_t)
 
 ~PowerCubeCtrl ()
 Destructor. More...
 

Protected Member Functions

bool getPositionAndStatus (int module_id, unsigned long *state, unsigned char *dio, float *position)
 

Protected Attributes

std::vector< double > m_accelerations
 
std::deque< std::vector< double > > m_cached_pos
 
bool m_CANDeviceOpened
 
int m_DeviceHandle
 
std::vector< unsigned char > m_dios
 
std::string m_ErrorMessage
 
double m_horizon
 
bool m_Initialized
 
ros::Time m_last_time_pub
 
std::vector< std::string > m_ModuleTypes
 
pthread_mutex_t m_mutex
 
PowerCubeCtrlParamsm_params
 
PC_CTRL_STATUS m_pc_status
 
std::vector< double > m_positions
 
std::vector< unsigned long > m_status
 
std::vector< double > m_velocities
 
std::vector< unsigned long > m_version
 

Detailed Description

Definition at line 37 of file PowerCubeCtrl.h.

Member Enumeration Documentation

Enumerator
PC_CTRL_OK 
PC_CTRL_NOT_HOMED 
PC_CTRL_ERR 
PC_CTRL_POW_VOLT_ERR 

Definition at line 46 of file PowerCubeCtrl.h.

Constructor & Destructor Documentation

PowerCubeCtrl::PowerCubeCtrl ( PowerCubeCtrlParams params)

Constructor.

Definition at line 36 of file PowerCubeCtrl.cpp.

PowerCubeCtrl::~PowerCubeCtrl ( )

Destructor.

Definition at line 55 of file PowerCubeCtrl.cpp.

Member Function Documentation

bool PowerCubeCtrl::Close ( )

Close.

Close CAN devices.

Definition at line 341 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::doHoming ( )

Waits until all Modules are homed.

Does homing for all Modules.

Homes only Schunk PW-Modules or PRL-Modules don't need to be homed.

PRL-Modules are ignored. PW-Modules are checked if they are homed. If not,homeing is executed.

getting offsets

wait until all modules are homed

start homing

timeout watchdog for homing

check result

Definition at line 1335 of file PowerCubeCtrl.cpp.

std::vector< double > PowerCubeCtrl::getAccelerations ( )

Gets the current accelerations.

Gets the current positions.

ToDo: calculate new accelerations before returning

Definition at line 1268 of file PowerCubeCtrl.cpp.

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

Get error message.

Definition at line 74 of file PowerCubeCtrl.h.

double PowerCubeCtrl::getHorizon ( )

Gets the horizon (sec).

The horizon is the maximum step size which will be commanded to the powercube chain. In case of a failure this is the time the powercube chain will continue to move until it is stopped.

Definition at line 997 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::getJointAngles ( std::vector< double > &  result)

get the current joint angles

Gets the current joint angles from device.

Definition at line 1277 of file PowerCubeCtrl.cpp.

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

get the current joint velocities (Rad/s)

Gets the current joint angular velocities from device.

Definition at line 1305 of file PowerCubeCtrl.cpp.

PC_CTRL_STATUS PowerCubeCtrl::getPC_Status ( ) const
inline

Get PC_Status message.

Definition at line 82 of file PowerCubeCtrl.h.

bool PowerCubeCtrl::getPositionAndStatus ( int  module_id,
unsigned long *  state,
unsigned char *  dio,
float *  position 
)
protected

Definition at line 1500 of file PowerCubeCtrl.cpp.

std::vector< double > PowerCubeCtrl::getPositions ( )

Gets the current positions.

Definition at line 1251 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::getStatus ( PC_CTRL_STATUS status,
std::vector< std::string > &  errorMessages 
)

Gets the status of the modules.

Definition at line 1138 of file PowerCubeCtrl.cpp.

std::vector< double > PowerCubeCtrl::getVelocities ( )

Gets the current velcities.

Gets the current velocities.

ToDo: calculate new velocities before returning

Definition at line 1259 of file PowerCubeCtrl.cpp.

std::vector< unsigned long > PowerCubeCtrl::getVersion ( )

Gets the firmware version of the modules.

Definition at line 1229 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::Init ( PowerCubeCtrlParams params)

Initializing.

ToDo: Check brief.

Initializing

Setting paramters initialized by PowerCubeCtrlParams.h

Output of current settings in the terminal

open device

reset all modules of the chain

check number of modules connected to the bus

Check if the modules are connected

retrieve serial number

retrieve version number

retrieve defined gear ratio

retrieve axis type (linear or rotational)

find out module_type

otherwise success

check if modules are in normal state

Definition at line 75 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::isInitialized ( ) const
inline

Checking if is initialized.

Definition at line 66 of file PowerCubeCtrl.h.

bool PowerCubeCtrl::MoveJointSpaceSync ( const std::vector< double > &  target_pos)

Send position goals to powercubes, the final angles will be reached simultaneously.

Move joints with calculated velocities and reach synchronously final position.

Parameters
velocitiesVector

Definition at line 366 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::MoveVel ( const std::vector< double > &  velocities)

Moves all cubes by the given velocities.

getting paramerters

getting limits

getting offsets

check dimensions

check velocity limit

check position limits

Types: PRL, PW, other

error handling

Definition at line 496 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::Recover ( )

Recovery after emergency stop or power supply failure.

Recovers the manipulator after an emergency stop.

modules successfully recovered

Definition at line 777 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setASyncMotion ( )

Configure powercubes to start all movements asynchronously.

Tells the Modules to start immediately

get config

set config to asynchronous

Definition at line 1046 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setHorizon ( double  horizon)

Sets the horizon (sec).

The horizon is the maximum step size which will be commanded to the powercube chain. In case of a failure this is the time the powercube chain will continue to move until it is stopped.

Definition at line 984 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setMaxAcceleration ( double  maxAcceleration)

Sets the maximum angular velocity (rad/s) for the Joints, use with care!

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 923 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setMaxAcceleration ( const std::vector< double > &  accelerations)

Sets the maximum angular acceleration (rad/s^2) for the Joints, use with care!

Definition at line 953 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setMaxVelocity ( double  maxVelocity)

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 864 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setMaxVelocity ( const std::vector< double > &  velocities)

Sets the maximum angular velocity (rad/s) for the Joints, use with care!

Definition at line 892 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::setSyncMotion ( )

Configure powercubes to start all movements synchronously.

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

get config

set config to synchronous

Definition at line 1007 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::statusMoving ( )

Returns true if any of the Joints are still moving.

Returns true if some cubes are still moving.

Should also return true if Joints are accelerating or decelerating

Definition at line 1236 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::Stop ( )

Stops the Manipulator immediately.

Stops the manipulator immediately.

getting paramerters

stop should be executes without checking any conditions

after halt the modules don't accept move commands any more, they first have to be reseted

reset all modules of the chain

Definition at line 732 of file PowerCubeCtrl.cpp.

bool PowerCubeCtrl::updateStates ( )

Returns the state of all modules.

Returns the current states.

Definition at line 1075 of file PowerCubeCtrl.cpp.

void PowerCubeCtrl::updateVelocities ( std::vector< double >  pos_temp,
double  delta_t 
)

Definition at line 698 of file PowerCubeCtrl.cpp.

Member Data Documentation

std::vector<double> PowerCubeCtrl::m_accelerations
protected

Definition at line 243 of file PowerCubeCtrl.h.

std::deque< std::vector<double> > PowerCubeCtrl::m_cached_pos
protected

Definition at line 241 of file PowerCubeCtrl.h.

bool PowerCubeCtrl::m_CANDeviceOpened
protected

Definition at line 231 of file PowerCubeCtrl.h.

int PowerCubeCtrl::m_DeviceHandle
protected

Definition at line 229 of file PowerCubeCtrl.h.

std::vector<unsigned char> PowerCubeCtrl::m_dios
protected

Definition at line 239 of file PowerCubeCtrl.h.

std::string PowerCubeCtrl::m_ErrorMessage
protected

Definition at line 249 of file PowerCubeCtrl.h.

double PowerCubeCtrl::m_horizon
protected

Definition at line 245 of file PowerCubeCtrl.h.

bool PowerCubeCtrl::m_Initialized
protected

Definition at line 230 of file PowerCubeCtrl.h.

ros::Time PowerCubeCtrl::m_last_time_pub
protected

Definition at line 247 of file PowerCubeCtrl.h.

std::vector<std::string> PowerCubeCtrl::m_ModuleTypes
protected

Definition at line 237 of file PowerCubeCtrl.h.

pthread_mutex_t PowerCubeCtrl::m_mutex
protected

Definition at line 227 of file PowerCubeCtrl.h.

PowerCubeCtrlParams* PowerCubeCtrl::m_params
protected

Definition at line 233 of file PowerCubeCtrl.h.

PC_CTRL_STATUS PowerCubeCtrl::m_pc_status
protected

Definition at line 234 of file PowerCubeCtrl.h.

std::vector<double> PowerCubeCtrl::m_positions
protected

Definition at line 240 of file PowerCubeCtrl.h.

std::vector<unsigned long> PowerCubeCtrl::m_status
protected

Definition at line 236 of file PowerCubeCtrl.h.

std::vector<double> PowerCubeCtrl::m_velocities
protected

Definition at line 242 of file PowerCubeCtrl.h.

std::vector<unsigned long> PowerCubeCtrl::m_version
protected

Definition at line 238 of file PowerCubeCtrl.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