motor.cpp
Go to the documentation of this file.
1 #include <canopen_402/motor.h>
2 #include <boost/thread/reverse_lock.hpp>
3 
4 namespace canopen
5 {
6 
8  boost::mutex::scoped_lock lock(mutex_);
9  return state_;
10 }
11 
13  static const uint16_t r = (1 << SW_Ready_To_Switch_On);
14  static const uint16_t s = (1 << SW_Switched_On);
15  static const uint16_t o = (1 << SW_Operation_enabled);
16  static const uint16_t f = (1 << SW_Fault);
17  static const uint16_t q = (1 << SW_Quick_stop);
18  static const uint16_t d = (1 << SW_Switch_on_disabled);
19 
20  InternalState new_state = Unknown;
21 
22  uint16_t state = sw & ( d | q | f | o | s | r );
23  switch ( state )
24  {
25  // ( d | q | f | o | s | r ):
26  case ( 0 | 0 | 0 | 0 | 0 | 0 ):
27  case ( 0 | q | 0 | 0 | 0 | 0 ):
28  new_state = Not_Ready_To_Switch_On;
29  break;
30 
31  case ( d | 0 | 0 | 0 | 0 | 0 ):
32  case ( d | q | 0 | 0 | 0 | 0 ):
33  new_state = Switch_On_Disabled;
34  break;
35 
36  case ( 0 | q | 0 | 0 | 0 | r ):
37  new_state = Ready_To_Switch_On;
38  break;
39 
40  case ( 0 | q | 0 | 0 | s | r ):
41  new_state = Switched_On;
42  break;
43 
44  case ( 0 | q | 0 | o | s | r ):
45  new_state = Operation_Enable;
46  break;
47 
48  case ( 0 | 0 | 0 | o | s | r ):
49  new_state = Quick_Stop_Active;
50  break;
51 
52  case ( 0 | 0 | f | o | s | r ):
53  case ( 0 | q | f | o | s | r ):
54  new_state = Fault_Reaction_Active;
55  break;
56 
57  case ( 0 | 0 | f | 0 | 0 | 0 ):
58  case ( 0 | q | f | 0 | 0 | 0 ):
59  new_state = Fault;
60  break;
61 
62  default:
63  ROSCANOPEN_WARN("canopen_402", "Motor is currently in an unknown state: " << std::hex << state << std::dec);
64  }
65  boost::mutex::scoped_lock lock(mutex_);
66  if(new_state != state_){
67  state_ = new_state;
68  cond_.notify_all();
69  }
70  return state_;
71 }
73  boost::mutex::scoped_lock lock(mutex_);
74  while(state_ == state && cond_.wait_until(lock, abstime) == boost::cv_status::no_timeout) {}
75  bool res = state != state_;
76  state = state_;
77  return res;
78 }
79 
81 
83  typedef State402 s;
84 
85  transitions_.reserve(32);
86 
87  Op disable_voltage(0,(1<<CW_Fault_Reset) | (1<<CW_Enable_Voltage));
88  /* 7*/ add(s::Ready_To_Switch_On, s::Switch_On_Disabled, disable_voltage);
89  /* 9*/ add(s::Operation_Enable, s::Switch_On_Disabled, disable_voltage);
90  /*10*/ add(s::Switched_On, s::Switch_On_Disabled, disable_voltage);
91  /*12*/ add(s::Quick_Stop_Active, s::Switch_On_Disabled, disable_voltage);
92 
93  Op automatic(0,0);
94  /* 0*/ add(s::Start, s::Not_Ready_To_Switch_On, automatic);
95  /* 1*/ add(s::Not_Ready_To_Switch_On, s::Switch_On_Disabled, automatic);
96  /*14*/ add(s::Fault_Reaction_Active, s::Fault, automatic);
97 
98  Op shutdown((1<<CW_Quick_Stop) | (1<<CW_Enable_Voltage), (1<<CW_Fault_Reset) | (1<<CW_Switch_On));
99  /* 2*/ add(s::Switch_On_Disabled, s::Ready_To_Switch_On, shutdown);
100  /* 6*/ add(s::Switched_On, s::Ready_To_Switch_On, shutdown);
101  /* 8*/ add(s::Operation_Enable, s::Ready_To_Switch_On, shutdown);
102 
103  Op switch_on((1<<CW_Quick_Stop) | (1<<CW_Enable_Voltage) | (1<<CW_Switch_On), (1<<CW_Fault_Reset) | (1<<CW_Enable_Operation));
104  /* 3*/ add(s::Ready_To_Switch_On, s::Switched_On, switch_on);
105  /* 5*/ add(s::Operation_Enable, s::Switched_On, switch_on);
106 
107  Op enable_operation((1<<CW_Quick_Stop) | (1<<CW_Enable_Voltage) | (1<<CW_Switch_On) | (1<<CW_Enable_Operation), (1<<CW_Fault_Reset));
108  /* 4*/ add(s::Switched_On, s::Operation_Enable, enable_operation);
109  /*16*/ add(s::Quick_Stop_Active, s::Operation_Enable, enable_operation);
110 
111  Op quickstop((1<<CW_Enable_Voltage), (1<<CW_Fault_Reset) | (1<<CW_Quick_Stop));
112  /* 7*/ add(s::Ready_To_Switch_On, s::Quick_Stop_Active, quickstop); // transit to Switch_On_Disabled
113  /*10*/ add(s::Switched_On, s::Quick_Stop_Active, quickstop); // transit to Switch_On_Disabled
114  /*11*/ add(s::Operation_Enable, s::Quick_Stop_Active, quickstop);
115 
116  // fault reset
117  /*15*/ add(s::Fault, s::Switch_On_Disabled, Op((1<<CW_Fault_Reset), 0));
118 }
120  switch(state){
121  case State402::Start:
123 
124  case State402::Fault:
127 
130 
132  return State402::Switched_On;
133 
138 
140  return State402::Fault;
141  }
142  throw std::out_of_range ("state value is illegal");
143 }
144 
146  try{
147  if(from != to){
148  State402::InternalState hop = to;
149  if(next){
150  if(to == State402::Operation_Enable) hop = nextStateForEnabling(from);
151  *next = hop;
152  }
153  transitions_.get(from, hop)(cw);
154  }
155  return true;
156  }
157  catch(...){
158  ROSCANOPEN_WARN("canopen_402", "illegal transition " << from << " -> " << to);
159  }
160  return false;
161 }
162 
163 template<uint16_t mask, uint16_t not_equal> struct masked_status_not_equal {
164  uint16_t &status_;
165  masked_status_not_equal(uint16_t &status) : status_(status) {}
166  bool operator()() const { return (status_ & mask) != not_equal; }
167 };
169  execute_ = false;
170  return read(0);
171 }
172 bool DefaultHomingMode::read(const uint16_t &sw) {
173  boost::mutex::scoped_lock lock(mutex_);
174  uint16_t old = status_;
175  status_ = sw & (MASK_Reached | MASK_Attained | MASK_Error);
176  if(old != status_){
177  cond_.notify_all();
178  }
179  return true;
180 }
182  cw = 0;
183  if(execute_){
184  cw.set(CW_StartHoming);
185  return true;
186  }
187  return false;
188 }
189 
191  if(!homing_method_.valid()){
192  return error(status, "homing method entry is not valid");
193  }
194 
195  if(homing_method_.get_cached() == 0){
196  return true;
197  }
198 
199  time_point prepare_time = get_abs_time(boost::chrono::seconds(1));
200  // ensure homing is not running
201  boost::mutex::scoped_lock lock(mutex_);
202  if(!cond_.wait_until(lock, prepare_time, masked_status_not_equal<MASK_Error | MASK_Reached, 0> (status_))){
203  return error(status, "could not prepare homing");
204  }
205  if(status_ & MASK_Error){
206  return error(status, "homing error before start");
207  }
208 
209  execute_ = true;
210 
211  // ensure start
213  return error(status, "homing did not start");
214  }
215  if(status_ & MASK_Error){
216  return error(status, "homing error at start");
217  }
218 
219  time_point finish_time = get_abs_time(boost::chrono::seconds(10)); //
220 
221  // wait for attained
222  if(!cond_.wait_until(lock, finish_time, masked_status_not_equal<MASK_Error | MASK_Attained, 0> (status_))){
223  return error(status, "homing not attained");
224  }
225  if(status_ & MASK_Error){
226  return error(status, "homing error during process");
227  }
228 
229  // wait for motion stop
230  if(!cond_.wait_until(lock, finish_time, masked_status_not_equal<MASK_Error | MASK_Reached, 0> (status_))){
231  return error(status, "homing did not stop");
232  }
233  if(status_ & MASK_Error){
234  return error(status, "homing error during stop");
235  }
236 
237  if((status_ & MASK_Reached) && (status_ & MASK_Attained)){
238  execute_ = false;
239  return true;
240  }
241 
242  return error(status, "something went wrong while homing");
243 }
244 
245 bool Motor402::setTarget(double val){
246  if(state_handler_.getState() == State402::Operation_Enable){
247  boost::mutex::scoped_lock lock(mode_mutex_);
248  return selected_mode_ && selected_mode_->setTarget(val);
249  }
250  return false;
251 }
252 bool Motor402::isModeSupported(uint16_t mode) { return mode != MotorBase::Homing && allocMode(mode); }
253 
254 bool Motor402::enterModeAndWait(uint16_t mode) {
255  LayerStatus s;
256  bool okay = mode != MotorBase::Homing && switchMode(s, mode);
257  if(!s.bounded<LayerStatus::Ok>()){
258  ROSCANOPEN_ERROR("canopen_402", "Could not switch to mode " << mode << ", reason: " << s.reason());
259  }
260  return okay;
261 }
262 
263 uint16_t Motor402::getMode() {
264  boost::mutex::scoped_lock lock(mode_mutex_);
265  return selected_mode_ ? selected_mode_->mode_id_ : MotorBase::No_Mode;
266 }
267 
269  if(!supported_drive_modes_.valid()) {
270  BOOST_THROW_EXCEPTION( std::runtime_error("Supported drive modes (object 6502) is not valid"));
271  }
272  return mode > 0 && mode <= 32 && (supported_drive_modes_.get_cached() & (1<<(mode-1)));
273 }
274 void Motor402::registerMode(uint16_t id, const ModeSharedPtr &m){
275  boost::mutex::scoped_lock map_lock(map_mutex_);
276  if(m && m->mode_id_ == id) modes_.insert(std::make_pair(id, m));
277 }
278 
280  ModeSharedPtr res;
281  if(isModeSupportedByDevice(mode)){
282  boost::mutex::scoped_lock map_lock(map_mutex_);
283  std::unordered_map<uint16_t, ModeSharedPtr >::iterator it = modes_.find(mode);
284  if(it != modes_.end()){
285  res = it->second;
286  }
287  }
288  return res;
289 }
290 
291 bool Motor402::switchMode(LayerStatus &status, uint16_t mode) {
292 
293  if(mode == MotorBase::No_Mode){
294  boost::mutex::scoped_lock lock(mode_mutex_);
295  selected_mode_.reset();
296  try{ // try to set mode
297  op_mode_.set(mode);
298  }catch(...){}
299  return true;
300  }
301 
302  ModeSharedPtr next_mode = allocMode(mode);
303  if(!next_mode){
304  status.error("Mode is not supported.");
305  return false;
306  }
307 
308  if(!next_mode->start()){
309  status.error("Could not start mode.");
310  return false;
311  }
312 
313  { // disable mode handler
314  boost::mutex::scoped_lock lock(mode_mutex_);
315 
316  if(mode_id_ == mode && selected_mode_ && selected_mode_->mode_id_ == mode){
317  // nothing to do
318  return true;
319  }
320 
321  selected_mode_.reset();
322  }
323 
324  if(!switchState(status, switching_state_)) return false;
325 
326  op_mode_.set(mode);
327 
328  bool okay = false;
329 
330  { // wait for switch
331  boost::mutex::scoped_lock lock(mode_mutex_);
332 
333  time_point abstime = get_abs_time(boost::chrono::seconds(5));
334  if(monitor_mode_){
335  while(mode_id_ != mode && mode_cond_.wait_until(lock, abstime) == boost::cv_status::no_timeout) {}
336  }else{
337  while(mode_id_ != mode && get_abs_time() < abstime){
338  boost::reverse_lock<boost::mutex::scoped_lock> reverse(lock); // unlock inside loop
339  op_mode_display_.get(); // poll
340  boost::this_thread::sleep_for(boost::chrono::milliseconds(20)); // wait some time
341  }
342  }
343 
344  if(mode_id_ == mode){
345  selected_mode_ = next_mode;
346  okay = true;
347  }else{
348  status.error("Mode switch timed out.");
349  op_mode_.set(mode_id_);
350  }
351  }
352 
353  if(!switchState(status, State402::Operation_Enable)) return false;
354 
355  return okay;
356 
357 }
358 
360  time_point abstime = get_abs_time(state_switch_timeout_);
361  State402::InternalState state = state_handler_.getState();
362  target_state_ = target;
363  while(state != target_state_){
364  boost::mutex::scoped_lock lock(cw_mutex_);
366  if(!Command402::setTransition(control_word_ ,state, target_state_ , &next)){
367  status.error("Could not set transition");
368  return false;
369  }
370  lock.unlock();
371  if(state != next && !state_handler_.waitForNewState(abstime, state)){
372  status.error("Transition timeout");
373  return false;
374  }
375  }
376  return state == target;
377 }
378 
379 bool Motor402::readState(LayerStatus &status, const LayerState &current_state){
380  uint16_t old_sw, sw = status_word_entry_.get(); // TODO: added error handling
381  old_sw = status_word_.exchange(sw);
382 
383  state_handler_.read(sw);
384 
385  boost::mutex::scoped_lock lock(mode_mutex_);
386  uint16_t new_mode = monitor_mode_ ? op_mode_display_.get() : op_mode_display_.get_cached();
387  if(selected_mode_ && selected_mode_->mode_id_ == new_mode){
388  if(!selected_mode_->read(sw)){
389  status.error("Mode handler has error");
390  }
391  }
392  if(new_mode != mode_id_){
393  mode_id_ = new_mode;
394  mode_cond_.notify_all();
395  }
396  if(selected_mode_ && selected_mode_->mode_id_ != new_mode){
397  status.warn("mode does not match");
398  }
399  if(sw & (1<<State402::SW_Internal_limit)){
400  if(old_sw & (1<<State402::SW_Internal_limit) || current_state != Ready){
401  status.warn("Internal limit active");
402  }else{
403  status.error("Internal limit active");
404  }
405  }
406 
407  return true;
408 }
409 void Motor402::handleRead(LayerStatus &status, const LayerState &current_state){
410  if(current_state > Off){
411  readState(status, current_state);
412  }
413 }
414 void Motor402::handleWrite(LayerStatus &status, const LayerState &current_state){
415  if(current_state > Off){
416  boost::mutex::scoped_lock lock(cw_mutex_);
417  control_word_ |= (1<<Command402::CW_Halt);
418  if(state_handler_.getState() == State402::Operation_Enable){
419  boost::mutex::scoped_lock lock(mode_mutex_);
420  Mode::OpModeAccesser cwa(control_word_);
421  bool okay = false;
422  if(selected_mode_ && selected_mode_->mode_id_ == mode_id_){
423  okay = selected_mode_->write(cwa);
424  } else {
425  cwa = 0;
426  }
427  if(okay) {
428  control_word_ &= ~(1<<Command402::CW_Halt);
429  }
430  }
431  if(start_fault_reset_.exchange(false)){
432  control_word_entry_.set_cached(control_word_ & ~(1<<Command402::CW_Fault_Reset));
433  }else{
434  control_word_entry_.set_cached(control_word_);
435  }
436  }
437 }
439  uint16_t sw = status_word_;
440  State402::InternalState state = state_handler_.getState();
441 
442  switch(state){
447  report.warn("Motor operation is not enabled");
449  break;
450 
452  report.error("Quick stop is active");
453  break;
454  case State402::Fault:
456  report.error("Motor has fault");
457  break;
458  case State402::Unknown:
459  report.error("State is unknown");
460  report.add("status_word", sw);
461  break;
462  }
463 
464  if(sw & (1<<State402::SW_Warning)){
465  report.warn("Warning bit is set");
466  }
467  if(sw & (1<<State402::SW_Internal_limit)){
468  report.error("Internal limit active");
469  }
470 }
472  for(std::unordered_map<uint16_t, AllocFuncType>::iterator it = mode_allocators_.begin(); it != mode_allocators_.end(); ++it){
473  (it->second)();
474  }
475 
476  if(!readState(status, Init)){
477  status.error("Could not read motor state");
478  return;
479  }
480  {
481  boost::mutex::scoped_lock lock(cw_mutex_);
482  control_word_ = 0;
483  start_fault_reset_ = true;
484  }
485  if(!switchState(status, State402::Operation_Enable)){
486  status.error("Could not enable motor");
487  return;
488  }
489 
490  ModeSharedPtr m = allocMode(MotorBase::Homing);
491  if(!m){
492  return; // homing not supported
493  }
494 
495  HomingMode *homing = dynamic_cast<HomingMode*>(m.get());
496 
497  if(!homing){
498  status.error("Homing mode has incorrect handler");
499  return;
500  }
501 
502  if(!switchMode(status, MotorBase::Homing)){
503  status.error("Could not enter homing mode");
504  return;
505  }
506 
507  if(!homing->executeHoming(status)){
508  status.error("Homing failed");
509  return;
510  }
511 
512  switchMode(status, No_Mode);
513 }
515  switchMode(status, MotorBase::No_Mode);
516  switchState(status, State402::Switch_On_Disabled);
517 }
519  State402::InternalState state = state_handler_.getState();
520  boost::mutex::scoped_lock lock(cw_mutex_);
521 
522  // do not demand quickstop in case of fault
523  if(state == State402::Fault_Reaction_Active || state == State402::Fault) return;
524 
525  if(state != State402::Operation_Enable){
526  target_state_ = state;
527  }else{
528  target_state_ = State402::Quick_Stop_Active;
529  if(!Command402::setTransition(control_word_ ,state, State402::Quick_Stop_Active, 0)){
530  status.warn("Could not quick stop");
531  }
532  }
533 }
535  start_fault_reset_ = true;
536  {
537  boost::mutex::scoped_lock lock(mode_mutex_);
538  if(selected_mode_ && !selected_mode_->start()){
539  status.error("Could not restart mode.");
540  return;
541  }
542  }
543  if(!switchState(status, State402::Operation_Enable)){
544  status.error("Could not enable motor");
545  return;
546  }
547 }
548 
549 } // namespace
virtual void handleRecover(LayerStatus &status)
Definition: motor.cpp:534
static bool setTransition(uint16_t &cw, const State402::InternalState &from, const State402::InternalState &to, State402::InternalState *next)
Definition: motor.cpp:145
InternalState state_
Definition: motor.h:57
masked_status_not_equal(uint16_t &status)
Definition: motor.cpp:165
virtual void handleWrite(LayerStatus &status, const LayerState &current_state)
Definition: motor.cpp:414
virtual void handleHalt(LayerStatus &status)
Definition: motor.cpp:518
const std::string reason() const
bool registerMode(uint16_t mode, Args &&... args)
Definition: motor.h:318
static const TransitionTable transitions_
Definition: motor.h:80
virtual bool isModeSupported(uint16_t mode)
Definition: motor.cpp:252
#define ROSCANOPEN_ERROR(name, args)
ModeSharedPtr allocMode(uint16_t mode)
Definition: motor.cpp:279
bool set(uint8_t bit)
Definition: motor.h:110
const void warn(const std::string &r)
virtual void handleDiag(LayerReport &report)
Definition: motor.cpp:438
virtual bool isModeSupportedByDevice(uint16_t mode)
Definition: motor.cpp:268
boost::mutex mutex_
Definition: motor.h:56
virtual bool read(const uint16_t &sw)
Definition: motor.cpp:172
boost::condition_variable cond_
Definition: motor.h:55
virtual bool enterModeAndWait(uint16_t mode)
Definition: motor.cpp:254
std::shared_ptr< Mode > ModeSharedPtr
Definition: motor.h:140
boost::chrono::high_resolution_clock::time_point time_point
static State402::InternalState nextStateForEnabling(State402::InternalState state)
Definition: motor.cpp:119
bool waitForNewState(const time_point &abstime, InternalState &state)
Definition: motor.cpp:72
virtual bool start()
Definition: motor.cpp:168
virtual uint16_t getMode()
Definition: motor.cpp:263
virtual bool setTarget(double val)
Definition: motor.cpp:245
virtual bool write(OpModeAccesser &cw)
Definition: motor.cpp:181
bool bounded() const
bool switchMode(LayerStatus &status, uint16_t mode)
Definition: motor.cpp:291
virtual bool executeHoming(canopen::LayerStatus &status)
Definition: motor.cpp:190
virtual void handleInit(LayerStatus &status)
Definition: motor.cpp:471
bool readState(LayerStatus &status, const LayerState &current_state)
Definition: motor.cpp:379
virtual void handleRead(LayerStatus &status, const LayerState &current_state)
Definition: motor.cpp:409
InternalState read(uint16_t sw)
Definition: motor.cpp:12
InternalState getState()
Definition: motor.cpp:7
void add(const std::string &key, const T &value)
virtual void handleShutdown(LayerStatus &status)
Definition: motor.cpp:514
const void error(const std::string &r)
#define ROSCANOPEN_WARN(name, args)
bool switchState(LayerStatus &status, const State402::InternalState &target)
Definition: motor.cpp:359
virtual bool executeHoming(canopen::LayerStatus &status)=0
time_point get_abs_time(const time_duration &timeout)


canopen_402
Author(s): Thiago de Freitas , Mathias Lüdtke
autogenerated on Mon Feb 28 2022 23:28:06