1 #ifndef CANOPEN_402_MOTOR_H 2 #define CANOPEN_402_MOTOR_H 6 #include <boost/function.hpp> 7 #include <boost/container/flat_map.hpp> 9 #include <boost/numeric/conversion/cast.hpp> 55 boost::condition_variable
cond_;
64 Op(uint16_t to_set ,uint16_t to_reset) : to_set_(to_set), to_reset_(to_reset) {}
66 val = (val & ~to_reset_) | to_set_;
70 boost::container::flat_map< std::pair<State402::InternalState, State402::InternalState>,
Op >
transitions_;
72 transitions_.insert(std::make_pair(std::make_pair(from, to), op));
77 return transitions_.at(std::make_pair(from, to));
89 CW_Enable_Operation=3,
90 CW_Operation_mode_specific0=4,
91 CW_Operation_mode_specific1=5,
92 CW_Operation_mode_specific2=6,
95 CW_Operation_mode_specific3=9,
97 CW_Manufacturer_specific0=11,
98 CW_Manufacturer_specific1=12,
99 CW_Manufacturer_specific2=13,
100 CW_Manufacturer_specific3=14,
101 CW_Manufacturer_specific4=15,
110 bool set(uint8_t bit){
111 uint16_t val = MASK & (1<<bit);
116 uint16_t val = MASK & (1<<bit);
120 bool get(uint8_t bit)
const {
return word_ & (1<<bit); }
121 uint16_t
get()
const {
return word_ & MASK; }
123 uint16_t was = word_;
124 word_ = (word_ & ~MASK) | (val & MASK);
132 Mode(uint16_t
id) : mode_id_(id) {}
134 virtual bool start() = 0;
135 virtual bool read(
const uint16_t &sw) = 0;
136 virtual bool write(OpModeAccesser& cw) = 0;
137 virtual bool setTarget(
const double &val) {
LOG(
"not implemented");
return false; }
151 if(boost::math::isnan(val)){
152 LOG(
"target command is not a number");
156 using boost::numeric_cast;
157 using boost::numeric::positive_overflow;
158 using boost::numeric::negative_overflow;
162 target_= numeric_cast<T>(val);
164 catch(negative_overflow&) {
165 LOG(
"Command " << val <<
" does not fit into target, clamping to min limit");
166 target_= std::numeric_limits<T>::min();
168 catch(positive_overflow&) {
169 LOG(
"Command " << val <<
" does not fit into target, clamping to max limit");
170 target_= std::numeric_limits<T>::max();
173 LOG(
"Was not able to cast command " << val);
180 virtual bool start() { has_target_ =
false;
return true; }
187 if(SUB) storage->entry(target_entry_, OBJ, SUB);
188 else storage->entry(target_entry_, OBJ);
190 virtual bool read(
const uint16_t &sw) {
return true;}
192 if(this->hasTarget()){
193 cw = cw.
get() | CW_MASK;
194 target_entry_.
set(this->getTarget());
197 cw = cw.
get() & ~CW_MASK;
227 storage->entry(target_position_, 0x607A);
230 virtual bool read(
const uint16_t &sw) { sw_ = sw;
return (sw & MASK_Error) == 0; }
232 cw.
set(CW_Immediate);
234 int32_t target = getTarget();
235 if((sw_ & MASK_Acknowledged) == 0 && target != last_target_){
236 if(cw.
get(CW_NewPoint)){
237 cw.
reset(CW_NewPoint);
239 target_position_.
set(target);
241 last_target_ = target;
243 }
else if (sw_ & MASK_Acknowledged){
244 cw.
reset(CW_NewPoint);
276 MASK_Attained = (1<<SW_Attained),
277 MASK_Error = (1<<SW_Error),
282 storage->entry(homing_method_, 0x6098);
284 virtual bool start();
285 virtual bool read(
const uint16_t &sw);
296 :
MotorBase(name), status_word_(0),control_word_(0),
298 monitor_mode_(settings.get_optional<bool>(
"monitor_mode", true)),
299 state_switch_timeout_(settings.get_optional<unsigned int>(
"state_switch_timeout", 5))
301 storage->entry(status_word_entry_, 0x6041);
302 storage->entry(control_word_entry_, 0x6040);
303 storage->entry(op_mode_display_, 0x6061);
304 storage->entry(op_mode_, 0x6060);
306 storage->entry(supported_drive_modes_, 0x6502);
312 virtual bool setTarget(
double val);
313 virtual bool enterModeAndWait(uint16_t mode);
314 virtual bool isModeSupported(uint16_t mode);
315 virtual uint16_t getMode();
318 return mode_allocators_.insert(std::make_pair(mode, boost::bind(&Motor402::createAndRegister<T>,
this, mode))).second;
320 template<
typename T,
typename T1>
bool registerMode(uint16_t mode,
const T1& t1) {
321 return mode_allocators_.insert(std::make_pair(mode, boost::bind(&Motor402::createAndRegister<T,T1>,
this, mode, t1))).second;
323 template<
typename T,
typename T1,
typename T2>
bool registerMode(uint16_t mode,
const T1& t1,
const T2& t2) {
324 return mode_allocators_.insert(std::make_pair(mode, boost::bind(&Motor402::createAndRegister<T,T1,T2>,
this, mode, t1, t2))).second;
354 if(isModeSupportedByDevice(mode)) registerMode(mode,
ModeSharedPtr(
new T()));
357 if(isModeSupportedByDevice(mode)) registerMode(mode,
ModeSharedPtr(
new T(t1)));
359 template<
typename T,
typename T1,
typename T2>
void createAndRegister(uint16_t mode,
const T1& t1,
const T2& t2){
360 if(isModeSupportedByDevice(mode)) registerMode(mode,
ModeSharedPtr(
new T(t1,t2)));
363 virtual bool isModeSupportedByDevice(uint16_t mode);
364 void registerMode(uint16_t
id,
const ModeSharedPtr &m);
366 ModeSharedPtr allocMode(uint16_t mode);
369 bool switchMode(
LayerStatus &status, uint16_t mode);
382 boost::unordered_map<uint16_t, ModeSharedPtr >
modes_;
canopen::ObjectStorage::Entry< TYPE > target_entry_
virtual void registerDefaultModes(ObjectStorageSharedPtr storage)
ProfiledPositionMode(ObjectStorageSharedPtr storage)
ModeForwardHelper< MotorBase::Velocity, int16_t, 0x6042, 0,(1<< Command402::CW_Operation_mode_specific0)|(1<< Command402::CW_Operation_mode_specific1)|(1<< Command402::CW_Operation_mode_specific2)> VelocityMode
boost::atomic< State402::InternalState > target_state_
boost::atomic< bool > start_fault_reset_
bool registerMode(uint16_t mode, const T1 &t1, const T2 &t2)
bool get(uint8_t bit) const
boost::atomic< uint16_t > status_word_
canopen::ObjectStorage::Entry< uint32_t > supported_drive_modes_
ModeTargetHelper(uint16_t mode)
static const TransitionTable transitions_
ModeForwardHelper< MotorBase::Profiled_Torque, int16_t, 0x6071, 0, 0 > ProfiledTorqueMode
boost::shared_ptr< MotorBase > MotorBaseSharedPtr
ModeForwardHelper< MotorBase::Cyclic_Synchronous_Position, int32_t, 0x607A, 0, 0 > CyclicSynchronousPositionMode
canopen::ObjectStorage::Entry< int32_t > target_position_
boost::unordered_map< uint16_t, AllocFuncType > mode_allocators_
virtual bool write(OpModeAccesser &cw)
WordAccessor & operator=(const uint16_t &val)
ModeSharedPtr selected_mode_
boost::condition_variable cond_
virtual bool read(const uint16_t &sw)
bool error(canopen::LayerStatus &status, const std::string &msg)
ModeForwardHelper< MotorBase::Profiled_Velocity, int32_t, 0x60FF, 0, 0 > ProfiledVelocityMode
void createAndRegister0(uint16_t mode)
boost::condition_variable cond_
void createAndRegister(uint16_t mode, const T1 &t1, const T2 &t2)
boost::chrono::high_resolution_clock::time_point time_point
canopen::ObjectStorage::Entry< uint16_t > status_word_entry_
ModeForwardHelper(ObjectStorageSharedPtr storage)
bool waitForNewState(const time_point &abstime, InternalState &state)
boost::function< void()> AllocFuncType
virtual bool read(const uint16_t &sw)
const boost::chrono::seconds state_switch_timeout_
canopen::ObjectStorage::Entry< int8_t > op_mode_
bool registerMode(uint16_t mode)
canopen::ObjectStorage::Entry< uint16_t > control_word_entry_
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
void operator()(uint16_t &val) const
ModeForwardHelper< MotorBase::Cyclic_Synchronous_Torque, int16_t, 0x6071, 0, 0 > CyclicSynchronousTorqueMode
DefaultHomingMode(ObjectStorageSharedPtr storage)
boost::condition_variable mode_cond_
ModeForwardHelper< MotorBase::Interpolated_Position, int32_t, 0x60C1, 0x01,(1<< Command402::CW_Operation_mode_specific0)> InterpolatedPositionMode
canopen::ObjectStorage::Entry< int8_t > op_mode_display_
bool registerMode(uint16_t mode, const T1 &t1)
WordAccessor(uint16_t &word)
Op(uint16_t to_set, uint16_t to_reset)
canopen::ObjectStorage::Entry< int8_t > homing_method_
InternalState read(uint16_t sw)
Motor402(const std::string &name, ObjectStorageSharedPtr storage, const canopen::Settings &settings)
void add(const State402::InternalState &from, const State402::InternalState &to, Op op)
boost::container::flat_map< std::pair< State402::InternalState, State402::InternalState >, Op > transitions_
boost::atomic< bool > has_target_
virtual bool write(Mode::OpModeAccesser &cw)
const void error(const std::string &r)
void createAndRegister(uint16_t mode, const T1 &t1)
boost::shared_ptr< Mode > ModeSharedPtr
ModeForwardHelper< MotorBase::Cyclic_Synchronous_Velocity, int32_t, 0x60FF, 0, 0 > CyclicSynchronousVelocityMode
virtual bool setTarget(const double &val)
ObjectStorage::ObjectStorageSharedPtr ObjectStorageSharedPtr
boost::atomic< bool > execute_
const State402::InternalState switching_state_
boost::unordered_map< uint16_t, ModeSharedPtr > modes_
virtual bool setTarget(const double &val)