Public Types | Public Member Functions | Private Attributes | List of all members
canopen::ProfiledPositionMode Class Reference

#include <motor.h>

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

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_
 

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 ( ObjectStorageSharedPtr  storage)
inline

Definition at line 226 of file motor.h.

Member Function Documentation

virtual bool canopen::ProfiledPositionMode::read ( const uint16_t &  sw)
inlinevirtual

Implements canopen::Mode.

Definition at line 230 of file motor.h.

virtual bool canopen::ProfiledPositionMode::start ( )
inlinevirtual

Reimplemented from canopen::ModeTargetHelper< int32_t >.

Definition at line 229 of file motor.h.

virtual bool canopen::ProfiledPositionMode::write ( OpModeAccesser cw)
inlinevirtual

Implements canopen::Mode.

Definition at line 231 of file motor.h.

Member Data Documentation

double canopen::ProfiledPositionMode::last_target_
private

Definition at line 213 of file motor.h.

uint16_t canopen::ProfiledPositionMode::sw_
private

Definition at line 214 of file motor.h.

canopen::ObjectStorage::Entry<int32_t> canopen::ProfiledPositionMode::target_position_
private

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 Fri May 14 2021 02:59:42