Public Types | Public Member Functions | Private Attributes
canopen::ProfiledPositionMode Class Reference

#include <motor.h>

Inheritance diagram for canopen::ProfiledPositionMode:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

Definition at line 211 of file motor.h.


Member Enumeration Documentation

Enumerator:
CW_NewPoint 
CW_Immediate 
CW_Blending 

Definition at line 221 of file motor.h.

Enumerator:
MASK_Reached 
MASK_Acknowledged 
MASK_Error 

Definition at line 216 of file motor.h.


Constructor & Destructor Documentation

canopen::ProfiledPositionMode::ProfiledPositionMode ( boost::shared_ptr< ObjectStorage storage) [inline]

Definition at line 226 of file motor.h.


Member Function Documentation

virtual bool canopen::ProfiledPositionMode::read ( const uint16_t &  sw) [inline, virtual]

Implements canopen::Mode.

Definition at line 230 of file motor.h.

virtual bool canopen::ProfiledPositionMode::start ( ) [inline, virtual]

Reimplemented from canopen::ModeTargetHelper< int32_t >.

Definition at line 229 of file motor.h.

virtual bool canopen::ProfiledPositionMode::write ( OpModeAccesser cw) [inline, virtual]

Implements canopen::Mode.

Definition at line 231 of file motor.h.


Member Data Documentation

Definition at line 213 of file motor.h.

Definition at line 214 of file motor.h.

Definition at line 212 of file motor.h.


The documentation for this class was generated from the following file:


canopen_402
Author(s): Thiago de Freitas , Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:49