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