#include <motor.h>
Public Types | |
enum | CW_bits { CW_NewPoint = Command402::CW_Operation_mode_specific0, CW_Immediate = Command402::CW_Operation_mode_specific1, CW_Blending = Command402::CW_Operation_mode_specific3 } |
enum | SW_masks { MASK_Reached = (1<<State402::SW_Target_reached), MASK_Acknowledged = (1<<State402::SW_Operation_mode_specific0), MASK_Error = (1<<State402::SW_Operation_mode_specific1) } |
Public Types inherited from canopen::Mode | |
typedef WordAccessor<(1<< Command402::CW_Operation_mode_specific0)|(1<< Command402::CW_Operation_mode_specific1)|(1<< Command402::CW_Operation_mode_specific2)|(1<< Command402::CW_Operation_mode_specific3)> | OpModeAccesser |
Public Member Functions | |
ProfiledPositionMode (ObjectStorageSharedPtr storage) | |
virtual bool | read (const uint16_t &sw) |
virtual bool | start () |
virtual bool | write (OpModeAccesser &cw) |
Public Member Functions inherited from canopen::ModeTargetHelper< int32_t > | |
int32_t | getTarget () |
bool | hasTarget () |
ModeTargetHelper (uint16_t mode) | |
virtual bool | setTarget (const double &val) |
Public Member Functions inherited from canopen::Mode | |
Mode (uint16_t id) | |
virtual | ~Mode () |
Private Attributes | |
double | last_target_ |
uint16_t | sw_ |
canopen::ObjectStorage::Entry< int32_t > | target_position_ |
Additional Inherited Members | |
Public Attributes inherited from canopen::Mode | |
const uint16_t | mode_id_ |
|
inline |
|
inlinevirtual |
Implements canopen::Mode.
|
inlinevirtual |
Reimplemented from canopen::ModeTargetHelper< int32_t >.
|
inlinevirtual |
Implements canopen::Mode.
|
private |