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         ROSCANOPEN_WARN(
"canopen_402", 
"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_;
 
   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);
 
   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);
 
  104      add(s::Ready_To_Switch_On, s::Switched_On, switch_on);
 
  105      add(s::Operation_Enable, s::Switched_On, switch_on);
 
  108      add(s::Switched_On, s::Operation_Enable, enable_operation);
 
  109      add(s::Quick_Stop_Active, s::Operation_Enable, enable_operation);
 
  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);
 
  142     throw std::out_of_range (
"state value is illegal");
 
  158         ROSCANOPEN_WARN(
"canopen_402", 
"illegal transition " << from << 
" -> " << to);
 
  166     bool operator()()
 const { 
return (status_ & mask) != not_equal; }
 
  173     boost::mutex::scoped_lock lock(mutex_);
 
  174     uint16_t old = status_;
 
  175     status_ = sw & (MASK_Reached | MASK_Attained | MASK_Error);
 
  184         cw.
set(CW_StartHoming);
 
  191     if(!homing_method_.valid()){
 
  192         return error(status, 
"homing method entry is not valid");
 
  195     if(homing_method_.get_cached() == 0){
 
  201     boost::mutex::scoped_lock lock(mutex_);
 
  203         return error(status, 
"could not prepare homing");
 
  205     if(status_ & MASK_Error){
 
  206         return error(status, 
"homing error before start");
 
  213         return error(status, 
"homing did not start");
 
  215     if(status_ & MASK_Error){
 
  216         return error(status, 
"homing error at start");
 
  223         return error(status, 
"homing not attained");
 
  225     if(status_ & MASK_Error){
 
  226         return error(status, 
"homing error during process");
 
  231         return error(status, 
"homing did not stop");
 
  233     if(status_ & MASK_Error){
 
  234         return error(status, 
"homing error during stop");
 
  237     if((status_ & MASK_Reached) && (status_ & MASK_Attained)){
 
  242     return error(status, 
"something went wrong while homing");
 
  247         boost::mutex::scoped_lock lock(mode_mutex_);
 
  248         return selected_mode_ && selected_mode_->setTarget(val);
 
  264     boost::mutex::scoped_lock lock(mode_mutex_);
 
  269     if(!supported_drive_modes_.valid()) {
 
  270         BOOST_THROW_EXCEPTION( std::runtime_error(
"Supported drive modes (object 6502) is not valid"));
 
  272     return mode > 0 && mode <= 32 && (supported_drive_modes_.get_cached() & (1<<(mode-1)));
 
  275     boost::mutex::scoped_lock map_lock(map_mutex_);
 
  276     if(m && m->mode_id_ == 
id) modes_.insert(std::make_pair(
id, m));
 
  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()){
 
  294         boost::mutex::scoped_lock lock(mode_mutex_);
 
  295         selected_mode_.reset();
 
  304         status.
error(
"Mode is not supported.");
 
  308     if(!next_mode->start()){
 
  309         status.
error(
"Could not start mode.");
 
  314         boost::mutex::scoped_lock lock(mode_mutex_);
 
  316         if(mode_id_ == mode && selected_mode_ && selected_mode_->mode_id_ == mode){
 
  321         selected_mode_.reset();
 
  324     if(!switchState(status, switching_state_)) 
return false;
 
  331         boost::mutex::scoped_lock lock(mode_mutex_);
 
  335             while(mode_id_ != mode && mode_cond_.wait_until(lock, abstime) == boost::cv_status::no_timeout) {}
 
  338                 boost::reverse_lock<boost::mutex::scoped_lock> reverse(lock); 
 
  339                 op_mode_display_.get(); 
 
  340                 boost::this_thread::sleep_for(boost::chrono::milliseconds(20)); 
 
  344         if(mode_id_ == mode){
 
  345             selected_mode_ = next_mode;
 
  348             status.
error(
"Mode switch timed out.");
 
  349             op_mode_.set(mode_id_);
 
  362     target_state_ = target;
 
  363     while(state != target_state_){
 
  364         boost::mutex::scoped_lock lock(cw_mutex_);
 
  367             status.
error(
"Could not set transition");
 
  371         if(state != next && !state_handler_.waitForNewState(abstime, state)){
 
  372             status.
error(
"Transition timeout");
 
  376     return state == target;
 
  380     uint16_t old_sw, sw = status_word_entry_.get(); 
 
  381     old_sw = status_word_.exchange(sw);
 
  383     state_handler_.read(sw);
 
  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");
 
  392     if(new_mode != mode_id_){
 
  394         mode_cond_.notify_all();
 
  396     if(selected_mode_ && selected_mode_->mode_id_ != new_mode){
 
  397         status.
warn(
"mode does not match");
 
  401             status.
warn(
"Internal limit active");
 
  403             status.
error(
"Internal limit active");
 
  410     if(current_state > Off){
 
  411         readState(status, current_state);
 
  415     if(current_state > Off){
 
  416         boost::mutex::scoped_lock lock(cw_mutex_);
 
  419             boost::mutex::scoped_lock lock(mode_mutex_);
 
  422             if(selected_mode_ && selected_mode_->mode_id_ == mode_id_){
 
  423                 okay = selected_mode_->write(cwa);
 
  431         if(start_fault_reset_.exchange(
false)){
 
  434             control_word_entry_.set_cached(control_word_);
 
  439     uint16_t sw = status_word_;
 
  447         report.
warn(
"Motor operation is not enabled");
 
  452         report.
error(
"Quick stop is active");
 
  456         report.
error(
"Motor has fault");
 
  459         report.
error(
"State is unknown");
 
  460         report.
add(
"status_word", sw);
 
  465         report.
warn(
"Warning bit is set");
 
  468         report.
error(
"Internal limit active");
 
  472     for(std::unordered_map<uint16_t, AllocFuncType>::iterator it = mode_allocators_.begin(); it != mode_allocators_.end(); ++it){
 
  476     if(!readState(status, Init)){
 
  477         status.
error(
"Could not read motor state");
 
  481         boost::mutex::scoped_lock lock(cw_mutex_);
 
  483         start_fault_reset_ = 
true;
 
  486         status.
error(
"Could not enable motor");
 
  498         status.
error(
"Homing mode has incorrect handler");
 
  503         status.
error(
"Could not enter homing mode");
 
  508         status.
error(
"Homing failed");
 
  512     switchMode(status, No_Mode);
 
  520     boost::mutex::scoped_lock lock(cw_mutex_);
 
  526         target_state_ = state;
 
  530             status.
warn(
"Could not quick stop");
 
  535     start_fault_reset_ = 
true;
 
  537         boost::mutex::scoped_lock lock(mode_mutex_);
 
  538         if(selected_mode_ && !selected_mode_->start()){
 
  539             status.
error(
"Could not restart mode.");
 
  544         status.
error(
"Could not enable motor");