Classes | Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
canopen::Motor402 Class Reference

#include <motor.h>

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

Classes

class  Allocator
 

Public Member Functions

virtual bool enterModeAndWait (uint16_t mode)
 
virtual uint16_t getMode ()
 
virtual bool isModeSupported (uint16_t mode)
 
 Motor402 (const std::string &name, ObjectStorageSharedPtr storage, const canopen::Settings &settings)
 
virtual void registerDefaultModes (ObjectStorageSharedPtr storage)
 
template<typename T >
bool registerMode (uint16_t mode)
 
template<typename T , typename T1 >
bool registerMode (uint16_t mode, const T1 &t1)
 
template<typename T , typename T1 , typename T2 >
bool registerMode (uint16_t mode, const T1 &t1, const T2 &t2)
 
virtual bool setTarget (double val)
 
- Public Member Functions inherited from canopen::Layer
void diag (LayerReport &report)
 
LayerState getLayerState ()
 
void halt (LayerStatus &status)
 
void init (LayerStatus &status)
 
 Layer (const std::string &n)
 
void read (LayerStatus &status)
 
void recover (LayerStatus &status)
 
void shutdown (LayerStatus &status)
 
void write (LayerStatus &status)
 
virtual ~Layer ()
 

Protected Member Functions

virtual void handleDiag (LayerReport &report)
 
virtual void handleHalt (LayerStatus &status)
 
virtual void handleInit (LayerStatus &status)
 
virtual void handleRead (LayerStatus &status, const LayerState &current_state)
 
virtual void handleRecover (LayerStatus &status)
 
virtual void handleShutdown (LayerStatus &status)
 
virtual void handleWrite (LayerStatus &status, const LayerState &current_state)
 
- Protected Member Functions inherited from canopen::MotorBase
 MotorBase (const std::string &name)
 

Private Types

typedef boost::function< void()> AllocFuncType
 

Private Member Functions

ModeSharedPtr allocMode (uint16_t mode)
 
template<typename T , typename T1 >
void createAndRegister (uint16_t mode, const T1 &t1)
 
template<typename T , typename T1 , typename T2 >
void createAndRegister (uint16_t mode, const T1 &t1, const T2 &t2)
 
template<typename T >
void createAndRegister0 (uint16_t mode)
 
virtual bool isModeSupportedByDevice (uint16_t mode)
 
bool readState (LayerStatus &status, const LayerState &current_state)
 
void registerMode (uint16_t id, const ModeSharedPtr &m)
 
bool switchMode (LayerStatus &status, uint16_t mode)
 
bool switchState (LayerStatus &status, const State402::InternalState &target)
 

Private Attributes

uint16_t control_word_
 
canopen::ObjectStorage::Entry< uint16_t > control_word_entry_
 
boost::mutex cw_mutex_
 
boost::mutex map_mutex_
 
boost::unordered_map< uint16_t, AllocFuncTypemode_allocators_
 
boost::condition_variable mode_cond_
 
uint16_t mode_id_
 
boost::mutex mode_mutex_
 
boost::unordered_map< uint16_t, ModeSharedPtrmodes_
 
const bool monitor_mode_
 
canopen::ObjectStorage::Entry< int8_t > op_mode_
 
canopen::ObjectStorage::Entry< int8_t > op_mode_display_
 
ModeSharedPtr selected_mode_
 
boost::atomic< bool > start_fault_reset_
 
State402 state_handler_
 
const boost::chrono::seconds state_switch_timeout_
 
boost::atomic< uint16_t > status_word_
 
canopen::ObjectStorage::Entry< uint16_t > status_word_entry_
 
canopen::ObjectStorage::Entry< uint32_t > supported_drive_modes_
 
const State402::InternalState switching_state_
 
boost::atomic< State402::InternalStatetarget_state_
 

Additional Inherited Members

- Public Types inherited from canopen::MotorBase
typedef boost::shared_ptr< MotorBaseMotorBaseSharedPtr
 
enum  OperationMode {
  No_Mode = 0, Profiled_Position = 1, Velocity = 2, Profiled_Velocity = 3,
  Profiled_Torque = 4, Reserved = 5, Homing = 6, Interpolated_Position = 7,
  Cyclic_Synchronous_Position = 8, Cyclic_Synchronous_Velocity = 9, Cyclic_Synchronous_Torque = 10
}
 
- Public Types inherited from canopen::Layer
enum  LayerState
 
- Public Attributes inherited from canopen::Layer
 Error
 
 Halt
 
 Init
 
const std::string name
 
 Off
 
 Ready
 
 Recover
 
 Shutdown
 

Detailed Description

Definition at line 291 of file motor.h.

Member Typedef Documentation

typedef boost::function<void()> canopen::Motor402::AllocFuncType
private

Definition at line 383 of file motor.h.

Constructor & Destructor Documentation

canopen::Motor402::Motor402 ( const std::string &  name,
ObjectStorageSharedPtr  storage,
const canopen::Settings settings 
)
inline

Definition at line 295 of file motor.h.

Member Function Documentation

ModeSharedPtr canopen::Motor402::allocMode ( uint16_t  mode)
private

Definition at line 278 of file motor.cpp.

template<typename T , typename T1 >
void canopen::Motor402::createAndRegister ( uint16_t  mode,
const T1 &  t1 
)
inlineprivate

Definition at line 356 of file motor.h.

template<typename T , typename T1 , typename T2 >
void canopen::Motor402::createAndRegister ( uint16_t  mode,
const T1 &  t1,
const T2 &  t2 
)
inlineprivate

Definition at line 359 of file motor.h.

template<typename T >
void canopen::Motor402::createAndRegister0 ( uint16_t  mode)
inlineprivate

Definition at line 353 of file motor.h.

bool canopen::Motor402::enterModeAndWait ( uint16_t  mode)
virtual

Implements canopen::MotorBase.

Definition at line 253 of file motor.cpp.

uint16_t canopen::Motor402::getMode ( )
virtual

Implements canopen::MotorBase.

Definition at line 262 of file motor.cpp.

void canopen::Motor402::handleDiag ( LayerReport report)
protectedvirtual

Implements canopen::Layer.

Definition at line 437 of file motor.cpp.

void canopen::Motor402::handleHalt ( LayerStatus status)
protectedvirtual

Implements canopen::Layer.

Definition at line 517 of file motor.cpp.

void canopen::Motor402::handleInit ( LayerStatus status)
protectedvirtual

Implements canopen::Layer.

Definition at line 470 of file motor.cpp.

void canopen::Motor402::handleRead ( LayerStatus status,
const LayerState current_state 
)
protectedvirtual

Implements canopen::Layer.

Definition at line 408 of file motor.cpp.

void canopen::Motor402::handleRecover ( LayerStatus status)
protectedvirtual

Implements canopen::Layer.

Definition at line 533 of file motor.cpp.

void canopen::Motor402::handleShutdown ( LayerStatus status)
protectedvirtual

Implements canopen::Layer.

Definition at line 513 of file motor.cpp.

void canopen::Motor402::handleWrite ( LayerStatus status,
const LayerState current_state 
)
protectedvirtual

Implements canopen::Layer.

Definition at line 413 of file motor.cpp.

bool canopen::Motor402::isModeSupported ( uint16_t  mode)
virtual

Implements canopen::MotorBase.

Definition at line 251 of file motor.cpp.

bool canopen::Motor402::isModeSupportedByDevice ( uint16_t  mode)
privatevirtual

Definition at line 267 of file motor.cpp.

bool canopen::Motor402::readState ( LayerStatus status,
const LayerState current_state 
)
private

Definition at line 378 of file motor.cpp.

virtual void canopen::Motor402::registerDefaultModes ( ObjectStorageSharedPtr  storage)
inlinevirtual

Reimplemented from canopen::MotorBase.

Definition at line 327 of file motor.h.

template<typename T >
bool canopen::Motor402::registerMode ( uint16_t  mode)
inline

Definition at line 317 of file motor.h.

template<typename T , typename T1 >
bool canopen::Motor402::registerMode ( uint16_t  mode,
const T1 &  t1 
)
inline

Definition at line 320 of file motor.h.

template<typename T , typename T1 , typename T2 >
bool canopen::Motor402::registerMode ( uint16_t  mode,
const T1 &  t1,
const T2 &  t2 
)
inline

Definition at line 323 of file motor.h.

void canopen::Motor402::registerMode ( uint16_t  id,
const ModeSharedPtr m 
)
private

Definition at line 273 of file motor.cpp.

bool canopen::Motor402::setTarget ( double  val)
virtual

Implements canopen::MotorBase.

Definition at line 244 of file motor.cpp.

bool canopen::Motor402::switchMode ( LayerStatus status,
uint16_t  mode 
)
private

Definition at line 290 of file motor.cpp.

bool canopen::Motor402::switchState ( LayerStatus status,
const State402::InternalState target 
)
private

Definition at line 358 of file motor.cpp.

Member Data Documentation

uint16_t canopen::Motor402::control_word_
private

Definition at line 373 of file motor.h.

canopen::ObjectStorage::Entry<uint16_t > canopen::Motor402::control_word_entry_
private

Definition at line 395 of file motor.h.

boost::mutex canopen::Motor402::cw_mutex_
private

Definition at line 374 of file motor.h.

boost::mutex canopen::Motor402::map_mutex_
private

Definition at line 381 of file motor.h.

boost::unordered_map<uint16_t, AllocFuncType> canopen::Motor402::mode_allocators_
private

Definition at line 384 of file motor.h.

boost::condition_variable canopen::Motor402::mode_cond_
private

Definition at line 388 of file motor.h.

uint16_t canopen::Motor402::mode_id_
private

Definition at line 387 of file motor.h.

boost::mutex canopen::Motor402::mode_mutex_
private

Definition at line 389 of file motor.h.

boost::unordered_map<uint16_t, ModeSharedPtr > canopen::Motor402::modes_
private

Definition at line 382 of file motor.h.

const bool canopen::Motor402::monitor_mode_
private

Definition at line 391 of file motor.h.

canopen::ObjectStorage::Entry<int8_t> canopen::Motor402::op_mode_
private

Definition at line 397 of file motor.h.

canopen::ObjectStorage::Entry<int8_t> canopen::Motor402::op_mode_display_
private

Definition at line 396 of file motor.h.

ModeSharedPtr canopen::Motor402::selected_mode_
private

Definition at line 386 of file motor.h.

boost::atomic<bool> canopen::Motor402::start_fault_reset_
private

Definition at line 375 of file motor.h.

State402 canopen::Motor402::state_handler_
private

Definition at line 379 of file motor.h.

const boost::chrono::seconds canopen::Motor402::state_switch_timeout_
private

Definition at line 392 of file motor.h.

boost::atomic<uint16_t> canopen::Motor402::status_word_
private

Definition at line 372 of file motor.h.

canopen::ObjectStorage::Entry<uint16_t> canopen::Motor402::status_word_entry_
private

Definition at line 394 of file motor.h.

canopen::ObjectStorage::Entry<uint32_t> canopen::Motor402::supported_drive_modes_
private

Definition at line 398 of file motor.h.

const State402::InternalState canopen::Motor402::switching_state_
private

Definition at line 390 of file motor.h.

boost::atomic<State402::InternalState> canopen::Motor402::target_state_
private

Definition at line 376 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 Sat May 4 2019 02:40:44