#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 Member Functions | |
| ProfiledPositionMode (boost::shared_ptr< ObjectStorage > storage) | |
| virtual bool | read (const uint16_t &sw) |
| virtual bool | start () |
| virtual bool | write (OpModeAccesser &cw) |
Private Attributes | |
| int32_t | last_target_ |
| uint16_t | sw_ |
| canopen::ObjectStorage::Entry < int32_t > | target_position_ |
| canopen::ProfiledPositionMode::ProfiledPositionMode | ( | boost::shared_ptr< ObjectStorage > | storage | ) | [inline] |
| virtual bool canopen::ProfiledPositionMode::read | ( | const uint16_t & | sw | ) | [inline, virtual] |
Implements canopen::Mode.
| virtual bool canopen::ProfiledPositionMode::start | ( | ) | [inline, virtual] |
Reimplemented from canopen::ModeTargetHelper< int32_t >.
| virtual bool canopen::ProfiledPositionMode::write | ( | OpModeAccesser & | cw | ) | [inline, virtual] |
Implements canopen::Mode.
int32_t canopen::ProfiledPositionMode::last_target_ [private] |
uint16_t canopen::ProfiledPositionMode::sw_ [private] |
canopen::ObjectStorage::Entry<int32_t> canopen::ProfiledPositionMode::target_position_ [private] |