#include <motor.h>

Public Types | |
| 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 | |
| Mode (uint16_t id) | |
| virtual bool | read (const uint16_t &sw)=0 |
| virtual bool | setTarget (const double &val) |
| virtual bool | start ()=0 |
| virtual bool | write (OpModeAccesser &cw)=0 |
| virtual | ~Mode () |
Public Attributes | |
| const uint16_t | mode_id_ |
| canopen::Mode::Mode | ( | uint16_t | id | ) | [inline] |
| virtual canopen::Mode::~Mode | ( | ) | [inline, virtual] |
| virtual bool canopen::Mode::read | ( | const uint16_t & | sw | ) | [pure virtual] |
| virtual bool canopen::Mode::setTarget | ( | const double & | val | ) | [inline, virtual] |
Reimplemented in canopen::ModeTargetHelper< T >, canopen::ModeTargetHelper< int32_t >, and canopen::ModeTargetHelper< TYPE >.
| virtual bool canopen::Mode::start | ( | ) | [pure virtual] |
| virtual bool canopen::Mode::write | ( | OpModeAccesser & | cw | ) | [pure virtual] |
| const uint16_t canopen::Mode::mode_id_ |