Public Types | Public Member Functions | Protected Attributes
PowerCubeCtrl Class Reference

#include <PowerCubeCtrl.h>

List of all members.

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

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 75 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 86 of file PowerCubeCtrl.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 78 of file PowerCubeCtrl.cpp.

Destructor.

Definition at line 97 of file PowerCubeCtrl.cpp.


Member Function Documentation

bool PowerCubeCtrl::Close ( void  )

Close.

Close CAN devices.

Definition at line 383 of file PowerCubeCtrl.cpp.

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

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

Get error message.

Definition at line 111 of file PowerCubeCtrl.h.

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

Get PC_Status message.

Definition at line 119 of file PowerCubeCtrl.h.

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

Gets the current positions.

Definition at line 1164 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 1051 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 1172 of file PowerCubeCtrl.cpp.

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

Gets the firmware version of the modules.

Definition at line 1142 of file PowerCubeCtrl.cpp.

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

bool PowerCubeCtrl::isInitialized ( ) const [inline]

Checking if is initialized.

Definition at line 103 of file PowerCubeCtrl.h.

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

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

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

Recovery after emergency stop or power supply failure.

Recovers the manipulator after an emergency stop.

modules successfully recovered

Definition at line 688 of file PowerCubeCtrl.cpp.

Configure powercubes to start all movements asynchronously.

Tells the Modules to start immediately

get config

set config to asynchronous

Definition at line 958 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 896 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 835 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 865 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 776 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 804 of file PowerCubeCtrl.cpp.

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

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

bool PowerCubeCtrl::Stop ( void  )

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

Returns the state of all modules.

Returns the current states.

Definition at line 987 of file PowerCubeCtrl.cpp.

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

Definition at line 609 of file PowerCubeCtrl.cpp.


Member Data Documentation

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

Definition at line 270 of file PowerCubeCtrl.h.

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

Definition at line 268 of file PowerCubeCtrl.h.

Definition at line 258 of file PowerCubeCtrl.h.

Definition at line 256 of file PowerCubeCtrl.h.

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

Definition at line 266 of file PowerCubeCtrl.h.

std::string PowerCubeCtrl::m_ErrorMessage [protected]

Definition at line 276 of file PowerCubeCtrl.h.

double PowerCubeCtrl::m_horizon [protected]

Definition at line 272 of file PowerCubeCtrl.h.

bool PowerCubeCtrl::m_Initialized [protected]

Definition at line 257 of file PowerCubeCtrl.h.

Definition at line 274 of file PowerCubeCtrl.h.

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

Definition at line 264 of file PowerCubeCtrl.h.

pthread_mutex_t PowerCubeCtrl::m_mutex [protected]

Definition at line 254 of file PowerCubeCtrl.h.

Definition at line 260 of file PowerCubeCtrl.h.

Definition at line 261 of file PowerCubeCtrl.h.

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

Definition at line 267 of file PowerCubeCtrl.h.

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

Definition at line 263 of file PowerCubeCtrl.h.

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

Definition at line 269 of file PowerCubeCtrl.h.

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

Definition at line 265 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 Oct 6 2014 07:31:10