motor_updater_test.cpp
Go to the documentation of this file.
00001 
00028 #include "sr_robot_lib/motor_updater.hpp"
00029 #include <gtest/gtest.h>
00030 
00031 struct UpdaterResult
00032 {
00033   bool svn_transmitted;
00034   bool svn_transmitted_once;
00035   int can_num_transmitted_counter;
00036 };
00037 
00038 class MotorUpdaterTest
00039 {
00040 public:
00041   MotorUpdaterTest()
00042   {}
00043 
00044   ~MotorUpdaterTest()
00045   {}
00046 
00047   UpdaterResult check_updates(double tolerancy)
00048   {
00049     std::vector<generic_updater::UpdateConfig> update_configs_vector;
00050 
00051     generic_updater::UpdateConfig test;
00052     test.what_to_update = MOTOR_DATA_SGL;
00053     test.when_to_update = -1.0;
00054     update_configs_vector.push_back(test);
00055 
00056     generic_updater::UpdateConfig test2;
00057     test2.what_to_update = MOTOR_DATA_VOLTAGE;
00058     test2.when_to_update = 5.0;
00059     update_configs_vector.push_back(test2);
00060 
00061     generic_updater::UpdateConfig test3;
00062     test3.what_to_update = MOTOR_DATA_CAN_NUM_RECEIVED;
00063     test3.when_to_update = 1.0;
00064     update_configs_vector.push_back(test3);
00065 
00066     generic_updater::MotorUpdater motor_updater = generic_updater::MotorUpdater(update_configs_vector, operation_mode::device_update_state::OPERATION);
00067 
00068     ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND* command = new ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND();
00069     motor_updater.build_command(command);
00070 
00071     bool svn_transmitted = false;
00072     bool svn_transmitted_once = false;
00073 
00074     int can_num_transmitted_counter = 0;
00075 
00076     ros::Time start = ros::Time::now();
00077     ros::Duration time_spent(0.0);
00078 
00079     while(time_spent.toSec() < 7.2)
00080     {
00081       ros::spinOnce();
00082       motor_updater.build_command(command);
00083 
00084       time_spent = ros::Time::now() - start;
00085 
00086       if(fabs(time_spent.toSec() - 5.0) < tolerancy )
00087       {
00088         if(command->from_motor_data_type == MOTOR_DATA_VOLTAGE)
00089         {
00090           ROS_INFO_STREAM("Correct data received at time : "<<time_spent);
00091           svn_transmitted = true;
00092 
00093           if(svn_transmitted_once)
00094             svn_transmitted_once = false;
00095           else
00096             svn_transmitted_once = true;
00097         }
00098       }
00099 
00100 
00101       if(fabs(time_spent.toSec()-((double)( (int)time_spent.toSec() ) ) ) < tolerancy )
00102       {
00103         if(command->from_motor_data_type == MOTOR_DATA_CAN_NUM_RECEIVED)
00104         {
00105           ROS_INFO_STREAM("Correct CAN data received at time : "<<time_spent);
00106           can_num_transmitted_counter ++;
00107         }
00108       }
00109       usleep(1000);
00110     }
00111 
00112     UpdaterResult updater_result;
00113     updater_result.svn_transmitted = svn_transmitted;
00114     updater_result.svn_transmitted_once = svn_transmitted_once;
00115     updater_result.can_num_transmitted_counter = can_num_transmitted_counter;
00116 
00117     delete command;
00118 
00119     return updater_result;
00120   }
00121 };
00122 
00123 TEST(Utils, motor_updater_freq_low_tolerancy)
00124 {
00125   MotorUpdaterTest mut = MotorUpdaterTest();
00126   UpdaterResult updater_result = mut.check_updates(0.01);
00127 
00128   EXPECT_TRUE(updater_result.svn_transmitted);
00129   EXPECT_TRUE(updater_result.svn_transmitted_once);
00130 
00131   EXPECT_EQ(updater_result.can_num_transmitted_counter, 7);
00132 }
00133 
00134 TEST(Utils, motor_updater_freq_medium_tolerancy)
00135 {
00136   MotorUpdaterTest mut = MotorUpdaterTest();
00137   UpdaterResult updater_result = mut.check_updates(0.05);
00138 
00139   EXPECT_TRUE(updater_result.svn_transmitted);
00140   EXPECT_TRUE(updater_result.svn_transmitted_once);
00141 
00142   EXPECT_EQ(updater_result.can_num_transmitted_counter, 7);
00143 }
00144 
00145 TEST(Utils, motor_updater_freq_high_tolerancy)
00146 {
00147   MotorUpdaterTest mut = MotorUpdaterTest();
00148   UpdaterResult updater_result = mut.check_updates(0.1);
00149 
00150   EXPECT_TRUE(updater_result.svn_transmitted);
00151   EXPECT_TRUE(updater_result.svn_transmitted_once);
00152 
00153   EXPECT_EQ(updater_result.can_num_transmitted_counter, 7);
00154 }
00155 
00156 
00157 int main(int argc, char **argv)
00158 {
00159   ros::init(argc, argv, "sr_edc_ethercat_drivers_test");
00160 
00161   testing::InitGoogleTest(&argc, argv);
00162   return RUN_ALL_TESTS();
00163 }
00164 
00165 /* For the emacs weenies in the crowd.
00166    Local Variables:
00167    c-basic-offset: 2
00168    End:
00169 */


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