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