motor_updater.cpp
Go to the documentation of this file.
00001 
00029 #include "sr_robot_lib/motor_updater.hpp"
00030 #include <boost/foreach.hpp>
00031 #include <iostream>
00032 
00033 namespace generic_updater
00034 {
00035   MotorUpdater::MotorUpdater(std::vector<UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
00036     : GenericUpdater(update_configs_vector, update_state), even_motors(1)
00037   {
00038   }
00039 
00040   MotorUpdater::~MotorUpdater()
00041   {
00042   }
00043 
00044   operation_mode::device_update_state::DeviceUpdateState MotorUpdater::build_init_command(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND* command)
00045   {
00046     if(!mutex->try_lock())
00047       return update_state;
00048 
00049     if (update_state == operation_mode::device_update_state::INITIALIZATION)
00050     {
00052       // First we ask for the next data we want to receive
00053       if(even_motors)
00054         even_motors = 0;
00055       else
00056       {
00057         even_motors = 1;
00058         which_data_to_request ++;
00059 
00060         if( which_data_to_request >= initialization_configs_vector.size() )
00061           which_data_to_request = 0;
00062       }
00063 
00064       command->which_motors = even_motors;
00065 
00066       //initialization data
00067       command->from_motor_data_type = static_cast<FROM_MOTOR_DATA_TYPE>(initialization_configs_vector[which_data_to_request].what_to_update);
00068       ROS_DEBUG_STREAM("Updating initialization data type: "<<command->from_motor_data_type << " | ["<<which_data_to_request<<"/"<<initialization_configs_vector.size()<<"] ");
00069     }
00070     else
00071     {
00072       //For the last message sent when a change of update_state happens (after that we use build_command instead of build_init_command)
00073       //we use the first important message and ask it to the even motors (0)
00074       //This is to avoid sending a random command
00075       command->which_motors = 0;
00076       command->from_motor_data_type = static_cast<FROM_MOTOR_DATA_TYPE>(important_update_configs_vector[0].what_to_update);
00077       ROS_DEBUG_STREAM("Updating important data type: "<<command->from_motor_data_type << " | ["<<which_data_to_request<<"/"<<important_update_configs_vector.size()<<"] ");
00078     }
00079 
00080     mutex->unlock();
00081 
00082     return update_state;
00083   }
00084 
00085   operation_mode::device_update_state::DeviceUpdateState MotorUpdater::build_command(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND* command)
00086   {
00087     if(!mutex->try_lock())
00088       return update_state;
00089 
00091     // First we ask for the next data we want to receive
00092     if(even_motors)
00093       even_motors = 0;
00094     else
00095     {
00096       even_motors = 1;
00097       which_data_to_request ++;
00098 
00099       if( which_data_to_request >= important_update_configs_vector.size() )
00100         which_data_to_request = 0;
00101     }
00102 
00103     command->which_motors = even_motors;
00104 
00105     if(!unimportant_data_queue.empty())
00106     {
00107       //an unimportant data is available
00108       command->from_motor_data_type = static_cast<FROM_MOTOR_DATA_TYPE>(unimportant_data_queue.front());
00109       unimportant_data_queue.pop();
00110 
00111       ROS_DEBUG_STREAM("Updating unimportant data type: "<<command->from_motor_data_type << " | queue size: "<<unimportant_data_queue.size());
00112     }
00113     else
00114     {
00115       //important data to update as often as possible
00116       command->from_motor_data_type = static_cast<FROM_MOTOR_DATA_TYPE>(important_update_configs_vector[which_data_to_request].what_to_update);
00117       ROS_DEBUG_STREAM("Updating important data type: "<<command->from_motor_data_type << " | ["<<which_data_to_request<<"/"<<important_update_configs_vector.size()<<"] ");
00118     }
00119 
00120     mutex->unlock();
00121 
00122     return update_state;
00123   }
00124 }
00125 
00126 
00127 
00128 /* For the emacs weenies in the crowd.
00129    Local Variables:
00130    c-basic-offset: 2
00131    End:
00132 */


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:02:16