motor_updater_test.cpp
Go to the documentation of this file.
1 
28 #include <gtest/gtest.h>
29 #include <vector>
30 
31 #define COMMAND_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND
32 
34 {
38 };
39 
41 {
42 public:
44  {
45  }
46 
48  {
49  }
50 
51  UpdaterResult check_updates(double tolerancy)
52  {
53  std::vector<generic_updater::UpdateConfig> update_configs_vector;
54 
57  test.when_to_update = -1.0;
58  update_configs_vector.push_back(test);
59 
62  test2.when_to_update = 5.0;
63  update_configs_vector.push_back(test2);
64 
67  test3.when_to_update = 1.0;
68  update_configs_vector.push_back(test3);
69 
71  update_configs_vector, operation_mode::device_update_state::OPERATION);
72 
74  motor_updater.build_command(command);
75 
76  bool git_transmitted = false;
77  bool git_transmitted_once = false;
78 
80 
82  ros::Duration time_spent(0.0);
83 
84  while (time_spent.toSec() < 7.2)
85  {
86  ros::spinOnce();
87  motor_updater.build_command(command);
88 
89  time_spent = ros::Time::now() - start;
90 
91  if (fabs(time_spent.toSec() - 5.0) < tolerancy)
92  {
93  if (command->from_motor_data_type == MOTOR_DATA_VOLTAGE)
94  {
95  ROS_INFO_STREAM("Correct data received at time : " << time_spent);
96  git_transmitted = true;
97 
98  if (git_transmitted_once)
99  {
100  git_transmitted_once = false;
101  }
102  else
103  {
104  git_transmitted_once = true;
105  }
106  }
107  }
108 
109 
110  if (fabs(time_spent.toSec() - (static_cast<double>(static_cast<int>(time_spent.toSec())))) < tolerancy)
111  {
112  if (command->from_motor_data_type == MOTOR_DATA_CAN_NUM_RECEIVED)
113  {
114  ROS_INFO_STREAM("Correct CAN data received at time : " << time_spent);
115  can_num_transmitted_counter++;
116  }
117  }
118  usleep(1000);
119  }
120 
121  UpdaterResult updater_result;
122  updater_result.git_transmitted = git_transmitted;
125 
126  delete command;
127 
128  return updater_result;
129  }
130 };
131 
132 TEST(Utils, motor_updater_freq_low_tolerancy)
133 {
135  UpdaterResult updater_result = mut.check_updates(0.01);
136 
137  EXPECT_TRUE(updater_result.git_transmitted);
138  EXPECT_TRUE(updater_result.git_transmitted_once);
139 
140  EXPECT_EQ(updater_result.can_num_transmitted_counter, 7);
141 }
142 
143 TEST(Utils, motor_updater_freq_medium_tolerancy)
144 {
146  UpdaterResult updater_result = mut.check_updates(0.05);
147 
148  EXPECT_TRUE(updater_result.git_transmitted);
149  EXPECT_TRUE(updater_result.git_transmitted_once);
150 
151  EXPECT_EQ(updater_result.can_num_transmitted_counter, 7);
152 }
153 
154 TEST(Utils, motor_updater_freq_high_tolerancy)
155 {
157  UpdaterResult updater_result = mut.check_updates(0.1);
158 
159  EXPECT_TRUE(updater_result.git_transmitted);
160  EXPECT_TRUE(updater_result.git_transmitted_once);
161 
162  EXPECT_EQ(updater_result.can_num_transmitted_counter, 7);
163 }
164 
165 
166 int main(int argc, char **argv)
167 {
168  ros::init(argc, argv, "sr_edc_ethercat_drivers_test");
169 
170  testing::InitGoogleTest(&argc, argv);
171  return RUN_ALL_TESTS();
172 }
173 
174 /* For the emacs weenies in the crowd.
175  Local Variables:
176  c-basic-offset: 2
177  End:
178 */
ROSCPP_DECL void start()
UpdaterResult check_updates(double tolerancy)
TEST(Utils, motor_updater_freq_low_tolerancy)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
MOTOR_DATA_SGL
operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command)
MOTOR_DATA_CAN_NUM_RECEIVED
ROSLIB_DECL std::string command(const std::string &cmd)
MOTOR_DATA_VOLTAGE
#define COMMAND_TYPE
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
static Time now()
ROSCPP_DECL void spinOnce()


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:57