18#ifndef CANOPEN_402_DRIVER_MODE_HPP
19#define CANOPEN_402_DRIVER_MODE_HPP
40 virtual bool read(
const uint16_t & sw) = 0;
42 virtual bool setTarget(
const double & val) {
return false; }
@ CW_Operation_mode_specific3
Definition command.hpp:69
@ CW_Operation_mode_specific1
Definition command.hpp:65
@ CW_Operation_mode_specific0
Definition command.hpp:64
@ CW_Operation_mode_specific2
Definition command.hpp:66
virtual bool read(const uint16_t &sw)=0
virtual bool setTarget(const double &val)
Definition mode.hpp:42
virtual ~Mode()
Definition mode.hpp:43
Mode(uint16_t id)
Definition mode.hpp:33
virtual bool write(OpModeAccesser &cw)=0
const uint16_t mode_id_
Definition mode.hpp:32
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
Definition mode.hpp:38
Definition word_accessor.hpp:27
Definition configuration_manager.hpp:28
std::shared_ptr< Mode > ModeSharedPtr
Definition mode.hpp:45