28 #include <gtest/gtest.h> 31 #define COMMAND_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND 53 std::vector<generic_updater::UpdateConfig> update_configs_vector;
58 update_configs_vector.push_back(test);
63 update_configs_vector.push_back(test2);
68 update_configs_vector.push_back(test3);
84 while (time_spent.
toSec() < 7.2)
91 if (fabs(time_spent.
toSec() - 5.0) < tolerancy)
96 git_transmitted =
true;
98 if (git_transmitted_once)
100 git_transmitted_once =
false;
104 git_transmitted_once =
true;
110 if (fabs(time_spent.
toSec() - (
static_cast<double>(
static_cast<int>(time_spent.
toSec())))) < tolerancy)
115 can_num_transmitted_counter++;
128 return updater_result;
132 TEST(Utils, motor_updater_freq_low_tolerancy)
143 TEST(Utils, motor_updater_freq_medium_tolerancy)
154 TEST(Utils, motor_updater_freq_high_tolerancy)
166 int main(
int argc,
char **argv)
168 ros::init(argc, argv,
"sr_edc_ethercat_drivers_test");
170 testing::InitGoogleTest(&argc, argv);
171 return RUN_ALL_TESTS();
int can_num_transmitted_counter
bool git_transmitted_once
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)
operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command)
MOTOR_DATA_CAN_NUM_RECEIVED
ROSLIB_DECL std::string command(const std::string &cmd)
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()