motor_data_checker.cpp
Go to the documentation of this file.
00001 
00027 #include "sr_robot_lib/motor_data_checker.hpp"
00028 #include <vector>
00029 
00030 namespace generic_updater
00031 {
00032   const double MotorDataChecker::timeout = 5.0;
00033 
00034   MotorDataChecker::MotorDataChecker(std::vector<shadow_joints::Joint> joints_vector,
00035                                      std::vector<UpdateConfig> initialization_configs_vector)
00036           : nh_tilde("~"), update_state(operation_mode::device_update_state::INITIALIZATION), init_max_duration(timeout)
00037   {
00038     init(joints_vector, initialization_configs_vector);
00039   }
00040 
00041   MotorDataChecker::~MotorDataChecker()
00042   {
00043     for (unsigned int i = 0; i < msg_checkers_.size(); i++)
00044     {
00045       for (unsigned int j = 0; j < msg_checkers_.at(i).msg_from_motor_checkers.size(); j++)
00046       {
00047         delete msg_checkers_.at(i).msg_from_motor_checkers.at(j);
00048       }
00049     }
00050   }
00051 
00052   void MotorDataChecker::init(std::vector<shadow_joints::Joint> joints_vector,
00053                               std::vector<UpdateConfig> initialization_configs_vector)
00054   {
00055     // Create a one-shot timer
00056     check_timeout_timer = nh_tilde.createTimer(init_max_duration,
00057                                                boost::bind(&MotorDataChecker::timer_callback, this, _1), true);
00058     update_state = operation_mode::device_update_state::INITIALIZATION;
00059     msg_checkers_.clear();
00060 
00061     std::vector<UpdateConfig>::iterator msg_it;
00062 
00063     for (msg_it = initialization_configs_vector.begin(); msg_it < initialization_configs_vector.end(); msg_it++)
00064     {
00065       MessageChecker tmp_msg_checker(static_cast<FROM_MOTOR_DATA_TYPE>(msg_it->what_to_update));
00066       for (std::vector<shadow_joints::Joint>::iterator joint = joints_vector.begin();
00067            joint != joints_vector.end();
00068            ++joint)
00069       {
00070         if (joint->has_actuator)
00071         {
00072           boost::shared_ptr<shadow_joints::MotorWrapper> motor_wrapper =
00073                   boost::static_pointer_cast<shadow_joints::MotorWrapper>(joint->actuator_wrapper);
00074           if (msg_it->what_to_update == MOTOR_DATA_SLOW_MISC)
00075           {
00076             tmp_msg_checker.msg_from_motor_checkers.push_back(new SlowMessageFromMotorChecker(motor_wrapper->motor_id));
00077           }
00078           else
00079           {
00080             tmp_msg_checker.msg_from_motor_checkers.push_back(new MessageFromMotorChecker(motor_wrapper->motor_id));
00081           }
00082         }
00083       }
00084       msg_checkers_.push_back(tmp_msg_checker);
00085     }
00086   }
00087 
00088   bool MotorDataChecker::check_message(std::vector<shadow_joints::Joint>::iterator joint_tmp,
00089                                        FROM_MOTOR_DATA_TYPE motor_data_type, int16u motor_slow_data_type)
00090   {
00091     int index_motor_data_type = 0;
00092 
00093     index_motor_data_type = find(motor_data_type);
00094     if (index_motor_data_type != (-1))
00095     {
00096       int index_motor_id = 0;
00097       boost::shared_ptr<shadow_joints::MotorWrapper> motor_wrapper =
00098               boost::static_pointer_cast<shadow_joints::MotorWrapper>(joint_tmp->actuator_wrapper);
00099       index_motor_id = msg_checkers_.at(index_motor_data_type).find(motor_wrapper->motor_id);
00100       if (index_motor_id != (-1))
00101       {
00102         if (motor_data_type == MOTOR_DATA_SLOW_MISC)
00103         {
00104           SlowMessageFromMotorChecker *ptr_tmp_checker =
00105                   dynamic_cast<SlowMessageFromMotorChecker *>(
00106                           msg_checkers_.at(index_motor_data_type).msg_from_motor_checkers.at(index_motor_id));
00107 
00108           if (ptr_tmp_checker != NULL)
00109           {
00110             ptr_tmp_checker->set_received(static_cast<FROM_MOTOR_SLOW_DATA_TYPE>(motor_slow_data_type));
00111           }
00112           else
00113           {
00114             ROS_ERROR_STREAM("Checker conversion failed");
00115           }
00116         }
00117         else
00118         {
00119           msg_checkers_.at(index_motor_data_type).msg_from_motor_checkers.at(index_motor_id)->set_received();
00120         }
00121       }
00122       else
00123       {
00124         ROS_ERROR_STREAM("Motor id not found: " << motor_wrapper->motor_id);
00125       }
00126     }
00127     return ((update_state == operation_mode::device_update_state::OPERATION) || is_everything_checked());
00128   }
00129 
00130   bool MotorDataChecker::is_everything_checked()
00131   {
00132     std::vector<MessageChecker>::iterator it;
00133 
00134     for (it = msg_checkers_.begin(); it < msg_checkers_.end(); it++)
00135     {
00136       std::vector<MessageFromMotorChecker *>::iterator it2;
00137 
00138       for (it2 = it->msg_from_motor_checkers.begin(); it2 < it->msg_from_motor_checkers.end(); it2++)
00139       {
00140         if (!(*it2)->get_received())
00141         {
00142           return false;
00143         }
00144       }
00145     }
00146 
00147     // all the motors are initialized -> we stop the timeout timer
00148     check_timeout_timer.stop();
00149     update_state = operation_mode::device_update_state::OPERATION;
00150     return true;
00151   }
00152 
00153   int MotorDataChecker::find(FROM_MOTOR_DATA_TYPE motor_data_type)
00154   {
00155     for (unsigned int i = 0; i < msg_checkers_.size(); i++)
00156     {
00157       if (msg_checkers_.at(i).msg_type == motor_data_type)
00158       {
00159         return i;
00160       }
00161     }
00162     return (-1);
00163   }
00164 
00165   void MotorDataChecker::timer_callback(const ros::TimerEvent &event)
00166   {
00167     if (update_state == operation_mode::device_update_state::INITIALIZATION)
00168     {
00169       update_state = operation_mode::device_update_state::OPERATION;
00170       ROS_ERROR_STREAM("Motor Initialization Timeout: the static information in the diagnostics may not be uptodate.");
00171     }
00172   }
00173 
00174   int MessageChecker::find(int motor_id)
00175   {
00176     for (unsigned int i = 0; i < msg_from_motor_checkers.size(); i++)
00177     {
00178       if (msg_from_motor_checkers.at(i)->motor_id_ == motor_id)
00179       {
00180         return i;
00181       }
00182     }
00183     return (-1);
00184   }
00185 
00186   SlowMessageFromMotorChecker::SlowMessageFromMotorChecker(int id)
00187           : MessageFromMotorChecker(id)
00188   {
00189     for (int i = 0; i <= MOTOR_SLOW_DATA_LAST; i++)
00190     {
00191       slow_data_received.at(i) = false;
00192     }
00193   }
00194 
00195   void SlowMessageFromMotorChecker::set_received(FROM_MOTOR_SLOW_DATA_TYPE slow_data_type)
00196   {
00197     if (received_ == false)
00198     {
00199       // Check the slow data type as received
00200       if (slow_data_type > MOTOR_SLOW_DATA_LAST)
00201       {
00202         ROS_ERROR_STREAM("Received bad slow_data_type: " << slow_data_type << " > " << slow_data_received.size());
00203         return;
00204       }
00205       slow_data_received.at(slow_data_type) = true;
00206 
00207       // look if every type is received, then change FROM_MOTOR_SLOW_DATA_TYPE general received state accordingly
00208       bool checked = true;
00209       for (int i = MOTOR_SLOW_DATA_SVN_REVISION; i <= MOTOR_SLOW_DATA_LAST; i++)
00210       {
00211         checked = checked && slow_data_received.at(i);
00212         if (!checked)
00213         {
00214           break;
00215         }
00216       }
00217       if (checked)
00218       {
00219         received_ = true;
00220       }
00221     }
00222   }
00223 
00224   void MessageFromMotorChecker::set_received()
00225   {
00226     received_ = true;
00227   }
00228 
00229   bool MessageFromMotorChecker::get_received()
00230   {
00231     return received_;
00232   }
00233 }  // namespace generic_updater
00234 
00235 /* For the emacs weenies in the crowd.
00236  Local Variables:
00237  c-basic-offset: 2
00238  End:
00239  */


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:26