27 #include <sr_mechanism_model/simple_transmission.hpp> 29 #include <gtest/gtest.h> 37 #define error_flag_names palm_0200_edc_error_flag_names 38 #define STATUS_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS 39 #define COMMAND_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND 67 tinyxml2::XMLElement *root;
68 tinyxml2::XMLElement *root_element;
69 tinyxml2::XMLDocument xml;
70 std::string robot_description;
73 xml.Parse(robot_description.c_str());
79 root_element = xml.RootElement();
80 root = xml.FirstChildElement(
"robot");
82 nh.
getParam(
"joint_to_sensor_mapping", joint_to_sensor_mapping);
85 hardware_interface::HardwareInterface *ehw =
static_cast<hardware_interface::HardwareInterface *
>(hw);
96 actuator =
static_cast<sr_actuator::SrMotorActuator *
>(hw->getActuator(name));
98 EXPECT_EQ(actuator->state_.device_id_, motor_id);
126 std::map<std::string, std::vector<double>> expected_processed_raw_values_coupled =
164 2301, 2738, 2154, 2693,
165 1978, 2680, 1840, 2677,
166 1707, 2664, 2287, 2334,
167 2095, 2242, 1953, 2230,
168 1807, 2223, 1685, 2206,
169 2243, 1839, 2112, 1772,
170 1928, 1764, 1762, 1755,
171 1650, 1683, 2219, 1387,
172 2056, 1375, 1884, 1370,
173 1741, 1337, 1630, 1329,
174 2206, 1141, 2055, 1132,
175 1877, 1114, 1730, 1103,
191 std::map<std::string, std::vector<double>> expected_processed_calibrated_values =
211 -0.0476325, -0.893474
223 0, -0.34906, -0.6981,
237 for (
auto const& x : lib_test->sr_hand_lib->coupled_calibration_map)
239 for (
int i=0; i < x.second.raw_values_coupled_.size(); ++i)
241 EXPECT_NEAR(x.second.raw_values_coupled_[i], expected_processed_raw_values_coupled[x.first][i], 0.01);
244 for (
int i=0; i < x.second.calibrated_values_.size(); ++i)
246 EXPECT_NEAR(x.second.calibrated_values_[i], expected_processed_calibrated_values[x.first][i], 0.01);
254 std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
255 const double expected_motor_position = 2.21185;
261 status_data->sensors[i] = i;
267 status_data->which_motors = 0;
270 status_data->which_motor_data_arrived = 0x00055555;
271 status_data->which_motor_data_had_errors = 0;
274 for (
unsigned int i = 0; i < 10; ++i)
276 status_data->motor_data_packet[i].torque = 4;
277 status_data->motor_data_packet[i].misc = 2 * i;
280 status_data->idle_time_us = 1;
282 for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
284 if (
"THJ1" == (*joint_tmp).joint_name)
290 lib_test->sr_hand_lib->calibrate_joint(joint_tmp, status_data);
295 const sr_actuator::SrMotorActuator *sr_actuator =
296 static_cast<sr_actuator::SrMotorActuator *
>(motor_wrapper->actuator);
298 EXPECT_NEAR(expected_motor_position, sr_actuator->motor_state_.position_unfiltered_, 0.01);
305 std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
312 status_data->sensors[i] = i;
318 status_data->which_motors = 0;
321 status_data->which_motor_data_arrived = 0x00055555;
322 status_data->which_motor_data_had_errors = 0;
325 for (
unsigned int i = 0; i < 10; ++i)
327 status_data->motor_data_packet[i].torque = 4;
328 status_data->motor_data_packet[i].misc = 2 * i;
331 status_data->idle_time_us = 1;
333 for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
335 if (
"THJ1" == (*joint_tmp).joint_name)
341 auto start = std::chrono::steady_clock::now();
342 for (
int i = 0; i < 20000; i++)
344 lib_test->sr_hand_lib->calibrate_joint(joint_tmp, status_data);
346 auto stop = std::chrono::steady_clock::now();
347 auto diff = stop -
start;
348 double diff_time =
static_cast<double>(std::chrono::duration <double, std::milli> (diff).count());
350 EXPECT_LT(diff_time, 100);
366 status_data->sensors[i] = i;
372 status_data->which_motors = 0;
375 status_data->which_motor_data_arrived = 0x00055555;
376 status_data->which_motor_data_had_errors = 0;
379 for (
unsigned int i = 0; i < 10; ++i)
381 status_data->motor_data_packet[i].torque = 4;
382 status_data->motor_data_packet[i].misc = 2 * i;
385 status_data->idle_time_us = 1;
388 lib_test->sr_hand_lib->update(status_data);
391 EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time, 1);
392 EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time_min, 1);
395 std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
396 for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
398 if (joint_tmp->has_actuator)
403 if (motor_wrapper->motor_id % 2 == 0)
405 const sr_actuator::SrMotorActuator *sr_actuator =
406 static_cast<sr_actuator::SrMotorActuator *
>(motor_wrapper->actuator);
408 ROS_ERROR_STREAM(
"last measured effort: " << sr_actuator->state_.last_measured_effort_ <<
" actuator: " <<
409 motor_wrapper->actuator);
411 EXPECT_FLOAT_EQ(sr_actuator->motor_state_.force_unfiltered_, 4.0);
412 EXPECT_EQ(sr_actuator->motor_state_.strain_gauge_right_, motor_wrapper->motor_id);
433 status_data->sensors[i] = i + 1;
439 status_data->which_motors = 0;
442 status_data->which_motor_data_arrived = 0x00055555;
443 status_data->which_motor_data_had_errors = 0;
446 for (
unsigned int i = 0; i < 10; ++i)
448 status_data->motor_data_packet[i].torque = i;
449 status_data->motor_data_packet[i].misc = 10 * i;
452 status_data->idle_time_us = 1;
455 lib_test->sr_hand_lib->update(status_data);
458 lib_test->check_hw_actuator(
"rh_FFJ4", 2, 3, 4.0);
681 std::vector<std::pair<std::string, bool> > flags;
683 flags = lib_test->sr_hand_lib->humanize_flags(0xFFFF);
685 EXPECT_EQ(flags.size(), 16);
687 for (
unsigned int i = 0; i < 16; ++i)
693 EXPECT_TRUE(flags[13].second);
694 EXPECT_TRUE(flags[14].second);
695 EXPECT_TRUE(flags[15].second);
702 int main(
int argc,
char **argv)
704 ros::init(argc, argv,
"calibration_test");
705 testing::InitGoogleTest(&argc, argv);
706 return RUN_ALL_TESTS();
SrRobotLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
TestHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< HandLibTestProtected > sr_hand_lib
HandLibTestProtected(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh)
int main(int argc, char **argv)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool getParam(const std::string &key, std::string &s) const
XmlRpc::XmlRpcValue joint_to_sensor_mapping
TEST(SrRobotLib, Initialization)
SrMotorHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
void calibrate_joint(std::vector< shadow_joints::Joint >::iterator joint_tmp, STATUS_TYPE *status_data)
void check_hw_actuator(std::string name, int motor_id, int id_in_enum, double expected_pos)
#define ROS_ERROR_STREAM(args)
sr_actuator::SrMotorActuator * actuator
std::vector< std::pair< std::string, bool > > humanize_flags(int flag)