2 #include <boost/thread/reverse_lock.hpp> 8 boost::mutex::scoped_lock lock(
mutex_);
16 static const uint16_t f = (1 <<
SW_Fault);
22 uint16_t state = sw & ( d | q | f | o | s | r );
26 case ( 0 | 0 | 0 | 0 | 0 | 0 ):
27 case ( 0 | q | 0 | 0 | 0 | 0 ):
31 case ( d | 0 | 0 | 0 | 0 | 0 ):
32 case ( d | q | 0 | 0 | 0 | 0 ):
36 case ( 0 | q | 0 | 0 | 0 | r ):
40 case ( 0 | q | 0 | 0 | s | r ):
44 case ( 0 | q | 0 | o | s | r ):
48 case ( 0 | 0 | 0 | o | s | r ):
52 case ( 0 | 0 | f | o | s | r ):
53 case ( 0 | q | f | o | s | r ):
57 case ( 0 | 0 | f | 0 | 0 | 0 ):
58 case ( 0 | q | f | 0 | 0 | 0 ):
63 LOG(
"Motor is currently in an unknown state: " << std::hex << state << std::dec);
65 boost::mutex::scoped_lock lock(
mutex_);
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_;
85 transitions_.reserve(32);
87 Op disable_voltage(0,(1<<CW_Fault_Reset) | (1<<CW_Enable_Voltage));
88 add(s::Ready_To_Switch_On, s::Switch_On_Disabled, disable_voltage);
89 add(s::Operation_Enable, s::Switch_On_Disabled, disable_voltage);
90 add(s::Switched_On, s::Switch_On_Disabled, disable_voltage);
91 add(s::Quick_Stop_Active, s::Switch_On_Disabled, disable_voltage);
94 add(s::Start, s::Not_Ready_To_Switch_On, automatic);
95 add(s::Not_Ready_To_Switch_On, s::Switch_On_Disabled, automatic);
96 add(s::Fault_Reaction_Active, s::Fault, automatic);
98 Op shutdown((1<<CW_Quick_Stop) | (1<<CW_Enable_Voltage), (1<<CW_Fault_Reset) | (1<<CW_Switch_On));
99 add(s::Switch_On_Disabled, s::Ready_To_Switch_On, shutdown);
100 add(s::Switched_On, s::Ready_To_Switch_On, shutdown);
101 add(s::Operation_Enable, s::Ready_To_Switch_On, shutdown);
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 add(s::Ready_To_Switch_On, s::Switched_On, switch_on);
105 add(s::Operation_Enable, s::Switched_On, switch_on);
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 add(s::Switched_On, s::Operation_Enable, enable_operation);
109 add(s::Quick_Stop_Active, s::Operation_Enable, enable_operation);
111 Op quickstop((1<<CW_Enable_Voltage), (1<<CW_Fault_Reset) | (1<<CW_Quick_Stop));
112 add(s::Ready_To_Switch_On, s::Quick_Stop_Active, quickstop);
113 add(s::Switched_On, s::Quick_Stop_Active, quickstop);
114 add(s::Operation_Enable, s::Quick_Stop_Active, quickstop);
117 add(s::Fault, s::Switch_On_Disabled,
Op((1<<CW_Fault_Reset), 0));
152 transitions_.get(from, hop)(cw);
157 LOG(
"illegal tranistion " << from <<
" -> " << to);
165 bool operator()()
const {
return (status_ & mask) != not_equal; }
172 boost::mutex::scoped_lock lock(
mutex_);
173 uint16_t old = status_;
174 status_ = sw & (MASK_Reached | MASK_Attained | MASK_Error);
183 cw.
set(CW_StartHoming);
190 if(!homing_method_.valid()){
191 return error(status,
"homing method entry is not valid");
194 if(homing_method_.get_cached() == 0){
200 boost::mutex::scoped_lock lock(
mutex_);
202 return error(status,
"could not prepare homing");
204 if(status_ & MASK_Error){
205 return error(status,
"homing error before start");
212 return error(status,
"homing did not start");
214 if(status_ & MASK_Error){
215 return error(status,
"homing error at start");
222 return error(status,
"homing not attained");
224 if(status_ & MASK_Error){
225 return error(status,
"homing error during process");
230 return error(status,
"homing did not stop");
232 if(status_ & MASK_Error){
233 return error(status,
"homing error during stop");
236 if((status_ & MASK_Reached) && (status_ & MASK_Attained)){
241 return error(status,
"something went wrong while homing");
246 boost::mutex::scoped_lock lock(mode_mutex_);
247 return selected_mode_ && selected_mode_->setTarget(val);
257 LOG(
"Could not switch to mode " << mode <<
", reason: " << s.
reason());
263 boost::mutex::scoped_lock lock(mode_mutex_);
268 if(!supported_drive_modes_.valid()) {
269 BOOST_THROW_EXCEPTION( std::runtime_error(
"Supported drive modes (object 6502) is not valid"));
271 return mode > 0 && mode <= 32 && (supported_drive_modes_.get_cached() & (1<<(mode-1)));
274 boost::mutex::scoped_lock map_lock(map_mutex_);
275 if(m && m->mode_id_ ==
id) modes_.insert(std::make_pair(
id, m));
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()){
293 boost::mutex::scoped_lock lock(mode_mutex_);
294 selected_mode_.reset();
303 status.
error(
"Mode is not supported.");
307 if(!next_mode->start()){
308 status.
error(
"Could not start mode.");
313 boost::mutex::scoped_lock lock(mode_mutex_);
315 if(mode_id_ == mode && selected_mode_ && selected_mode_->mode_id_ == mode){
320 selected_mode_.reset();
323 if(!switchState(status, switching_state_))
return false;
330 boost::mutex::scoped_lock lock(mode_mutex_);
334 while(mode_id_ != mode && mode_cond_.wait_until(lock, abstime) == boost::cv_status::no_timeout) {}
337 boost::reverse_lock<boost::mutex::scoped_lock> reverse(lock);
338 op_mode_display_.get();
339 boost::this_thread::sleep_for(boost::chrono::milliseconds(20));
343 if(mode_id_ == mode){
344 selected_mode_ = next_mode;
347 status.
error(
"Mode switch timed out.");
348 op_mode_.set(mode_id_);
361 target_state_ = target;
362 while(state != target_state_){
363 boost::mutex::scoped_lock lock(cw_mutex_);
366 status.
error(
"Could not set transition");
370 if(state != next && !state_handler_.waitForNewState(abstime, state)){
371 status.
error(
"Transition timeout");
375 return state == target;
379 uint16_t old_sw, sw = status_word_entry_.get();
380 old_sw = status_word_.exchange(sw);
382 state_handler_.read(sw);
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");
391 if(new_mode != mode_id_){
393 mode_cond_.notify_all();
395 if(selected_mode_ && selected_mode_->mode_id_ != new_mode){
396 status.
warn(
"mode does not match");
400 status.
warn(
"Internal limit active");
402 status.
error(
"Internal limit active");
409 if(current_state > Off){
410 readState(status, current_state);
414 if(current_state > Off){
415 boost::mutex::scoped_lock lock(cw_mutex_);
418 boost::mutex::scoped_lock lock(mode_mutex_);
421 if(selected_mode_ && selected_mode_->mode_id_ == mode_id_){
422 okay = selected_mode_->write(cwa);
430 if(start_fault_reset_.exchange(
false)){
433 control_word_entry_.set_cached(control_word_);
438 uint16_t sw = status_word_;
446 report.
warn(
"Motor operation is not enabled");
451 report.
error(
"Quick stop is active");
455 report.
error(
"Motor has fault");
458 report.
error(
"State is unknown");
459 report.
add(
"status_word", sw);
464 report.
warn(
"Warning bit is set");
467 report.
error(
"Internal limit active");
471 for(boost::unordered_map<uint16_t, AllocFuncType>::iterator it = mode_allocators_.begin(); it != mode_allocators_.end(); ++it){
475 if(!readState(status, Init)){
476 status.
error(
"Could not read motor state");
480 boost::mutex::scoped_lock lock(cw_mutex_);
482 start_fault_reset_ =
true;
485 status.
error(
"Could not enable motor");
497 status.
error(
"Homing mode has incorrect handler");
502 status.
error(
"Could not enter homing mode");
507 status.
error(
"Homing failed");
511 switchMode(status, No_Mode);
519 boost::mutex::scoped_lock lock(cw_mutex_);
525 target_state_ = state;
529 status.
warn(
"Could not quick stop");
534 start_fault_reset_ =
true;
536 boost::mutex::scoped_lock lock(mode_mutex_);
537 if(selected_mode_ && !selected_mode_->start()){
538 status.
error(
"Could not restart mode.");
543 status.
error(
"Could not enable motor");
virtual void handleRecover(LayerStatus &status)
static bool setTransition(uint16_t &cw, const State402::InternalState &from, const State402::InternalState &to, State402::InternalState *next)
masked_status_not_equal(uint16_t &status)
virtual void handleWrite(LayerStatus &status, const LayerState ¤t_state)
virtual void handleHalt(LayerStatus &status)
static const TransitionTable transitions_
virtual bool isModeSupported(uint16_t mode)
ModeSharedPtr allocMode(uint16_t mode)
const void warn(const std::string &r)
virtual void handleDiag(LayerReport &report)
virtual bool isModeSupportedByDevice(uint16_t mode)
const std::string reason() const
virtual bool read(const uint16_t &sw)
boost::condition_variable cond_
virtual bool enterModeAndWait(uint16_t mode)
boost::chrono::high_resolution_clock::time_point time_point
static State402::InternalState nextStateForEnabling(State402::InternalState state)
bool waitForNewState(const time_point &abstime, InternalState &state)
bool registerMode(uint16_t mode)
virtual uint16_t getMode()
virtual bool setTarget(double val)
virtual bool write(OpModeAccesser &cw)
bool switchMode(LayerStatus &status, uint16_t mode)
virtual bool executeHoming(canopen::LayerStatus &status)
virtual void handleInit(LayerStatus &status)
bool readState(LayerStatus &status, const LayerState ¤t_state)
virtual void handleRead(LayerStatus &status, const LayerState ¤t_state)
InternalState read(uint16_t sw)
void add(const std::string &key, const T &value)
virtual void handleShutdown(LayerStatus &status)
const void error(const std::string &r)
bool switchState(LayerStatus &status, const State402::InternalState &target)
boost::shared_ptr< Mode > ModeSharedPtr
virtual bool executeHoming(canopen::LayerStatus &status)=0
time_point get_abs_time(const time_duration &timeout)