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  LOG("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 }
143 
145  try{
146  if(from != to){
147  State402::InternalState hop = to;
148  if(next){
149  if(to == State402::Operation_Enable) hop = nextStateForEnabling(from);
150  *next = hop;
151  }
152  transitions_.get(from, hop)(cw);
153  }
154  return true;
155  }
156  catch(...){
157  LOG("illegal tranistion " << from << " -> " << to);
158  }
159  return false;
160 }
161 
162 template<uint16_t mask, uint16_t not_equal> struct masked_status_not_equal {
163  uint16_t &status_;
164  masked_status_not_equal(uint16_t &status) : status_(status) {}
165  bool operator()() const { return (status_ & mask) != not_equal; }
166 };
168  execute_ = false;
169  return read(0);
170 }
171 bool DefaultHomingMode::read(const uint16_t &sw) {
172  boost::mutex::scoped_lock lock(mutex_);
173  uint16_t old = status_;
174  status_ = sw & (MASK_Reached | MASK_Attained | MASK_Error);
175  if(old != status_){
176  cond_.notify_all();
177  }
178  return true;
179 }
181  cw = 0;
182  if(execute_){
183  cw.set(CW_StartHoming);
184  return true;
185  }
186  return false;
187 }
188 
190  if(!homing_method_.valid()){
191  return error(status, "homing method entry is not valid");
192  }
193 
194  if(homing_method_.get_cached() == 0){
195  return true;
196  }
197 
198  time_point prepare_time = get_abs_time(boost::chrono::seconds(1));
199  // ensure homing is not running
200  boost::mutex::scoped_lock lock(mutex_);
201  if(!cond_.wait_until(lock, prepare_time, masked_status_not_equal<MASK_Error | MASK_Reached, 0> (status_))){
202  return error(status, "could not prepare homing");
203  }
204  if(status_ & MASK_Error){
205  return error(status, "homing error before start");
206  }
207 
208  execute_ = true;
209 
210  // ensure start
212  return error(status, "homing did not start");
213  }
214  if(status_ & MASK_Error){
215  return error(status, "homing error at start");
216  }
217 
218  time_point finish_time = get_abs_time(boost::chrono::seconds(10)); //
219 
220  // wait for attained
221  if(!cond_.wait_until(lock, finish_time, masked_status_not_equal<MASK_Error | MASK_Attained, 0> (status_))){
222  return error(status, "homing not attained");
223  }
224  if(status_ & MASK_Error){
225  return error(status, "homing error during process");
226  }
227 
228  // wait for motion stop
229  if(!cond_.wait_until(lock, finish_time, masked_status_not_equal<MASK_Error | MASK_Reached, 0> (status_))){
230  return error(status, "homing did not stop");
231  }
232  if(status_ & MASK_Error){
233  return error(status, "homing error during stop");
234  }
235 
236  if((status_ & MASK_Reached) && (status_ & MASK_Attained)){
237  execute_ = false;
238  return true;
239  }
240 
241  return error(status, "something went wrong while homing");
242 }
243 
244 bool Motor402::setTarget(double val){
245  if(state_handler_.getState() == State402::Operation_Enable){
246  boost::mutex::scoped_lock lock(mode_mutex_);
247  return selected_mode_ && selected_mode_->setTarget(val);
248  }
249  return false;
250 }
251 bool Motor402::isModeSupported(uint16_t mode) { return mode != MotorBase::Homing && allocMode(mode); }
252 
253 bool Motor402::enterModeAndWait(uint16_t mode) {
254  LayerStatus s;
255  bool okay = mode != MotorBase::Homing && switchMode(s, mode);
256  if(!s.bounded<LayerStatus::Ok>()){
257  LOG("Could not switch to mode " << mode << ", reason: " << s.reason());
258  }
259  return okay;
260 }
261 
262 uint16_t Motor402::getMode() {
263  boost::mutex::scoped_lock lock(mode_mutex_);
264  return selected_mode_ ? selected_mode_->mode_id_ : MotorBase::No_Mode;
265 }
266 
268  if(!supported_drive_modes_.valid()) {
269  BOOST_THROW_EXCEPTION( std::runtime_error("Supported drive modes (object 6502) is not valid"));
270  }
271  return mode > 0 && mode <= 32 && (supported_drive_modes_.get_cached() & (1<<(mode-1)));
272 }
273 void Motor402::registerMode(uint16_t id, const ModeSharedPtr &m){
274  boost::mutex::scoped_lock map_lock(map_mutex_);
275  if(m && m->mode_id_ == id) modes_.insert(std::make_pair(id, m));
276 }
277 
279  ModeSharedPtr res;
280  if(isModeSupportedByDevice(mode)){
281  boost::mutex::scoped_lock map_lock(map_mutex_);
282  boost::unordered_map<uint16_t, ModeSharedPtr >::iterator it = modes_.find(mode);
283  if(it != modes_.end()){
284  res = it->second;
285  }
286  }
287  return res;
288 }
289 
290 bool Motor402::switchMode(LayerStatus &status, uint16_t mode) {
291 
292  if(mode == MotorBase::No_Mode){
293  boost::mutex::scoped_lock lock(mode_mutex_);
294  selected_mode_.reset();
295  try{ // try to set mode
296  op_mode_.set(mode);
297  }catch(...){}
298  return true;
299  }
300 
301  ModeSharedPtr next_mode = allocMode(mode);
302  if(!next_mode){
303  status.error("Mode is not supported.");
304  return false;
305  }
306 
307  if(!next_mode->start()){
308  status.error("Could not start mode.");
309  return false;
310  }
311 
312  { // disable mode handler
313  boost::mutex::scoped_lock lock(mode_mutex_);
314 
315  if(mode_id_ == mode && selected_mode_ && selected_mode_->mode_id_ == mode){
316  // nothing to do
317  return true;
318  }
319 
320  selected_mode_.reset();
321  }
322 
323  if(!switchState(status, switching_state_)) return false;
324 
325  op_mode_.set(mode);
326 
327  bool okay = false;
328 
329  { // wait for switch
330  boost::mutex::scoped_lock lock(mode_mutex_);
331 
332  time_point abstime = get_abs_time(boost::chrono::seconds(5));
333  if(monitor_mode_){
334  while(mode_id_ != mode && mode_cond_.wait_until(lock, abstime) == boost::cv_status::no_timeout) {}
335  }else{
336  while(mode_id_ != mode && get_abs_time() < abstime){
337  boost::reverse_lock<boost::mutex::scoped_lock> reverse(lock); // unlock inside loop
338  op_mode_display_.get(); // poll
339  boost::this_thread::sleep_for(boost::chrono::milliseconds(20)); // wait some time
340  }
341  }
342 
343  if(mode_id_ == mode){
344  selected_mode_ = next_mode;
345  okay = true;
346  }else{
347  status.error("Mode switch timed out.");
348  op_mode_.set(mode_id_);
349  }
350  }
351 
352  if(!switchState(status, State402::Operation_Enable)) return false;
353 
354  return okay;
355 
356 }
357 
359  time_point abstime = get_abs_time(state_switch_timeout_);
360  State402::InternalState state = state_handler_.getState();
361  target_state_ = target;
362  while(state != target_state_){
363  boost::mutex::scoped_lock lock(cw_mutex_);
365  if(!Command402::setTransition(control_word_ ,state, target_state_ , &next)){
366  status.error("Could not set transition");
367  return false;
368  }
369  lock.unlock();
370  if(state != next && !state_handler_.waitForNewState(abstime, state)){
371  status.error("Transition timeout");
372  return false;
373  }
374  }
375  return state == target;
376 }
377 
378 bool Motor402::readState(LayerStatus &status, const LayerState &current_state){
379  uint16_t old_sw, sw = status_word_entry_.get(); // TODO: added error handling
380  old_sw = status_word_.exchange(sw);
381 
382  state_handler_.read(sw);
383 
384  boost::mutex::scoped_lock lock(mode_mutex_);
385  uint16_t new_mode = monitor_mode_ ? op_mode_display_.get() : op_mode_display_.get_cached();
386  if(selected_mode_ && selected_mode_->mode_id_ == new_mode){
387  if(!selected_mode_->read(sw)){
388  status.error("Mode handler has error");
389  }
390  }
391  if(new_mode != mode_id_){
392  mode_id_ = new_mode;
393  mode_cond_.notify_all();
394  }
395  if(selected_mode_ && selected_mode_->mode_id_ != new_mode){
396  status.warn("mode does not match");
397  }
398  if(sw & (1<<State402::SW_Internal_limit)){
399  if(old_sw & (1<<State402::SW_Internal_limit) || current_state != Ready){
400  status.warn("Internal limit active");
401  }else{
402  status.error("Internal limit active");
403  }
404  }
405 
406  return true;
407 }
408 void Motor402::handleRead(LayerStatus &status, const LayerState &current_state){
409  if(current_state > Off){
410  readState(status, current_state);
411  }
412 }
413 void Motor402::handleWrite(LayerStatus &status, const LayerState &current_state){
414  if(current_state > Off){
415  boost::mutex::scoped_lock lock(cw_mutex_);
416  control_word_ |= (1<<Command402::CW_Halt);
417  if(state_handler_.getState() == State402::Operation_Enable){
418  boost::mutex::scoped_lock lock(mode_mutex_);
419  Mode::OpModeAccesser cwa(control_word_);
420  bool okay = false;
421  if(selected_mode_ && selected_mode_->mode_id_ == mode_id_){
422  okay = selected_mode_->write(cwa);
423  } else {
424  cwa = 0;
425  }
426  if(okay) {
427  control_word_ &= ~(1<<Command402::CW_Halt);
428  }
429  }
430  if(start_fault_reset_.exchange(false)){
431  control_word_entry_.set_cached(control_word_ & ~(1<<Command402::CW_Fault_Reset));
432  }else{
433  control_word_entry_.set_cached(control_word_);
434  }
435  }
436 }
438  uint16_t sw = status_word_;
439  State402::InternalState state = state_handler_.getState();
440 
441  switch(state){
446  report.warn("Motor operation is not enabled");
448  break;
449 
451  report.error("Quick stop is active");
452  break;
453  case State402::Fault:
455  report.error("Motor has fault");
456  break;
457  case State402::Unknown:
458  report.error("State is unknown");
459  report.add("status_word", sw);
460  break;
461  }
462 
463  if(sw & (1<<State402::SW_Warning)){
464  report.warn("Warning bit is set");
465  }
466  if(sw & (1<<State402::SW_Internal_limit)){
467  report.error("Internal limit active");
468  }
469 }
471  for(boost::unordered_map<uint16_t, AllocFuncType>::iterator it = mode_allocators_.begin(); it != mode_allocators_.end(); ++it){
472  (it->second)();
473  }
474 
475  if(!readState(status, Init)){
476  status.error("Could not read motor state");
477  return;
478  }
479  {
480  boost::mutex::scoped_lock lock(cw_mutex_);
481  control_word_ = 0;
482  start_fault_reset_ = true;
483  }
484  if(!switchState(status, State402::Operation_Enable)){
485  status.error("Could not enable motor");
486  return;
487  }
488 
489  ModeSharedPtr m = allocMode(MotorBase::Homing);
490  if(!m){
491  return; // homing not supported
492  }
493 
494  HomingMode *homing = dynamic_cast<HomingMode*>(m.get());
495 
496  if(!homing){
497  status.error("Homing mode has incorrect handler");
498  return;
499  }
500 
501  if(!switchMode(status, MotorBase::Homing)){
502  status.error("Could not enter homing mode");
503  return;
504  }
505 
506  if(!homing->executeHoming(status)){
507  status.error("Homing failed");
508  return;
509  }
510 
511  switchMode(status, No_Mode);
512 }
514  switchMode(status, MotorBase::No_Mode);
515  switchState(status, State402::Switch_On_Disabled);
516 }
518  State402::InternalState state = state_handler_.getState();
519  boost::mutex::scoped_lock lock(cw_mutex_);
520 
521  // do not demand quickstop in case of fault
522  if(state == State402::Fault_Reaction_Active || state == State402::Fault) return;
523 
524  if(state != State402::Operation_Enable){
525  target_state_ = state;
526  }else{
527  target_state_ = State402::Quick_Stop_Active;
528  if(!Command402::setTransition(control_word_ ,state, State402::Quick_Stop_Active, 0)){
529  status.warn("Could not quick stop");
530  }
531  }
532 }
534  start_fault_reset_ = true;
535  {
536  boost::mutex::scoped_lock lock(mode_mutex_);
537  if(selected_mode_ && !selected_mode_->start()){
538  status.error("Could not restart mode.");
539  return;
540  }
541  }
542  if(!switchState(status, State402::Operation_Enable)){
543  status.error("Could not enable motor");
544  return;
545  }
546 }
547 
548 } // namespace
virtual void handleRecover(LayerStatus &status)
Definition: motor.cpp:533
static bool setTransition(uint16_t &cw, const State402::InternalState &from, const State402::InternalState &to, State402::InternalState *next)
Definition: motor.cpp:144
InternalState state_
Definition: motor.h:57
masked_status_not_equal(uint16_t &status)
Definition: motor.cpp:164
virtual void handleWrite(LayerStatus &status, const LayerState &current_state)
Definition: motor.cpp:413
virtual void handleHalt(LayerStatus &status)
Definition: motor.cpp:517
static const TransitionTable transitions_
Definition: motor.h:80
virtual bool isModeSupported(uint16_t mode)
Definition: motor.cpp:251
ModeSharedPtr allocMode(uint16_t mode)
Definition: motor.cpp:278
bool set(uint8_t bit)
Definition: motor.h:110
const void warn(const std::string &r)
virtual void handleDiag(LayerReport &report)
Definition: motor.cpp:437
virtual bool isModeSupportedByDevice(uint16_t mode)
Definition: motor.cpp:267
boost::mutex mutex_
Definition: motor.h:56
const std::string reason() const
virtual bool read(const uint16_t &sw)
Definition: motor.cpp:171
boost::condition_variable cond_
Definition: motor.h:55
virtual bool enterModeAndWait(uint16_t mode)
Definition: motor.cpp:253
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:167
bool registerMode(uint16_t mode)
Definition: motor.h:317
#define LOG(log)
virtual uint16_t getMode()
Definition: motor.cpp:262
virtual bool setTarget(double val)
Definition: motor.cpp:244
virtual bool write(OpModeAccesser &cw)
Definition: motor.cpp:180
bool switchMode(LayerStatus &status, uint16_t mode)
Definition: motor.cpp:290
virtual bool executeHoming(canopen::LayerStatus &status)
Definition: motor.cpp:189
virtual void handleInit(LayerStatus &status)
Definition: motor.cpp:470
bool readState(LayerStatus &status, const LayerState &current_state)
Definition: motor.cpp:378
virtual void handleRead(LayerStatus &status, const LayerState &current_state)
Definition: motor.cpp:408
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:513
const void error(const std::string &r)
bool switchState(LayerStatus &status, const State402::InternalState &target)
Definition: motor.cpp:358
boost::shared_ptr< Mode > ModeSharedPtr
Definition: motor.h:140
virtual bool executeHoming(canopen::LayerStatus &status)=0
time_point get_abs_time(const time_duration &timeout)
bool bounded() const


canopen_402
Author(s): Thiago de Freitas , Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:44