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

#include <motor.h>

List of all members.

Public Types

enum  InternalState {
  Unknown = 0, Start = 0, Not_Ready_To_Switch_On = 1, Switch_On_Disabled = 2,
  Ready_To_Switch_On = 3, Switched_On = 4, Operation_Enable = 5, Quick_Stop_Active = 6,
  Fault_Reaction_Active = 7, Fault = 8
}
enum  StatusWord {
  SW_Ready_To_Switch_On = 0, SW_Switched_On = 1, SW_Operation_enabled = 2, SW_Fault = 3,
  SW_Voltage_enabled = 4, SW_Quick_stop = 5, SW_Switch_on_disabled = 6, SW_Warning = 7,
  SW_Manufacturer_specific0 = 8, SW_Remote = 9, SW_Target_reached = 10, SW_Internal_limit = 11,
  SW_Operation_mode_specific0 = 12, SW_Operation_mode_specific1 = 13, SW_Manufacturer_specific1 = 14, SW_Manufacturer_specific2 = 15
}

Public Member Functions

InternalState getState ()
InternalState read (uint16_t sw)
 State402 ()
bool waitForNewState (const time_point &abstime, InternalState &state)

Private Attributes

boost::condition_variable cond_
boost::mutex mutex_
InternalState state_

Detailed Description

Definition at line 16 of file motor.h.


Member Enumeration Documentation

Enumerator:
Unknown 
Start 
Not_Ready_To_Switch_On 
Switch_On_Disabled 
Ready_To_Switch_On 
Switched_On 
Operation_Enable 
Quick_Stop_Active 
Fault_Reaction_Active 
Fault 

Definition at line 37 of file motor.h.

Enumerator:
SW_Ready_To_Switch_On 
SW_Switched_On 
SW_Operation_enabled 
SW_Fault 
SW_Voltage_enabled 
SW_Quick_stop 
SW_Switch_on_disabled 
SW_Warning 
SW_Manufacturer_specific0 
SW_Remote 
SW_Target_reached 
SW_Internal_limit 
SW_Operation_mode_specific0 
SW_Operation_mode_specific1 
SW_Manufacturer_specific1 
SW_Manufacturer_specific2 

Definition at line 18 of file motor.h.


Constructor & Destructor Documentation

Definition at line 53 of file motor.h.


Member Function Documentation

Definition at line 7 of file motor.cpp.

Definition at line 12 of file motor.cpp.

Definition at line 72 of file motor.cpp.


Member Data Documentation

boost::condition_variable canopen::State402::cond_ [private]

Definition at line 55 of file motor.h.

boost::mutex canopen::State402::mutex_ [private]

Definition at line 56 of file motor.h.

Definition at line 57 of file motor.h.


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


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