27 #include <sr_mechanism_model/simple_transmission.hpp> 28 #include <gtest/gtest.h> 36 #define error_flag_names palm_0200_edc_error_flag_names 37 #define STATUS_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS 38 #define COMMAND_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND 67 TiXmlElement *root_element;
69 std::string robot_description;
72 xml.Parse(robot_description.c_str());
78 root_element = xml.RootElement();
79 root = xml.FirstChildElement(
"robot");
81 nh.
getParam(
"joint_to_sensor_mapping", joint_to_sensor_mapping);
84 hardware_interface::HardwareInterface *ehw =
static_cast<hardware_interface::HardwareInterface *
>(hw);
95 actuator =
static_cast<sr_actuator::SrMotorActuator *
>(hw->getActuator(name));
97 EXPECT_EQ(actuator->state_.device_id_, motor_id);
125 std::map<std::string, std::vector<double>> expected_processed_raw_values_coupled =
163 2301, 2738, 2154, 2693,
164 1978, 2680, 1840, 2677,
165 1707, 2664, 2287, 2334,
166 2095, 2242, 1953, 2230,
167 1807, 2223, 1685, 2206,
168 2243, 1839, 2112, 1772,
169 1928, 1764, 1762, 1755,
170 1650, 1683, 2219, 1387,
171 2056, 1375, 1884, 1370,
172 1741, 1337, 1630, 1329,
173 2206, 1141, 2055, 1132,
174 1877, 1114, 1730, 1103,
190 std::map<std::string, std::vector<double>> expected_processed_calibrated_values =
210 -0.0476325, -0.893474
222 0, -0.34906, -0.6981,
236 for (
auto const& x : lib_test->sr_hand_lib->coupled_calibration_map)
238 for (
int i=0; i < x.second.raw_values_coupled_.size(); ++i)
240 EXPECT_NEAR(x.second.raw_values_coupled_[i], expected_processed_raw_values_coupled[x.first][i], 0.01);
243 for (
int i=0; i < x.second.calibrated_values_.size(); ++i)
245 EXPECT_NEAR(x.second.calibrated_values_[i], expected_processed_calibrated_values[x.first][i], 0.01);
253 std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
254 const double expected_motor_position = 2.21185;
260 status_data->sensors[i] = i;
266 status_data->which_motors = 0;
269 status_data->which_motor_data_arrived = 0x00055555;
270 status_data->which_motor_data_had_errors = 0;
273 for (
unsigned int i = 0; i < 10; ++i)
275 status_data->motor_data_packet[i].torque = 4;
276 status_data->motor_data_packet[i].misc = 2 * i;
279 status_data->idle_time_us = 1;
281 for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
283 if (
"THJ1" == (*joint_tmp).joint_name)
289 lib_test->sr_hand_lib->calibrate_joint(joint_tmp, status_data);
294 const sr_actuator::SrMotorActuator *sr_actuator =
295 static_cast<sr_actuator::SrMotorActuator *
>(motor_wrapper->actuator);
297 EXPECT_NEAR(expected_motor_position, sr_actuator->motor_state_.position_unfiltered_, 0.01);
304 std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
311 status_data->sensors[i] = i;
317 status_data->which_motors = 0;
320 status_data->which_motor_data_arrived = 0x00055555;
321 status_data->which_motor_data_had_errors = 0;
324 for (
unsigned int i = 0; i < 10; ++i)
326 status_data->motor_data_packet[i].torque = 4;
327 status_data->motor_data_packet[i].misc = 2 * i;
330 status_data->idle_time_us = 1;
332 for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
334 if (
"THJ1" == (*joint_tmp).joint_name)
340 auto start = std::chrono::steady_clock::now();
341 for (
int i = 0; i < 20000; i++)
343 lib_test->sr_hand_lib->calibrate_joint(joint_tmp, status_data);
345 auto stop = std::chrono::steady_clock::now();
346 auto diff = stop -
start;
347 double diff_time =
static_cast<double>(std::chrono::duration <double, std::milli> (diff).count());
349 EXPECT_LT(diff_time, 100);
365 status_data->sensors[i] = i;
371 status_data->which_motors = 0;
374 status_data->which_motor_data_arrived = 0x00055555;
375 status_data->which_motor_data_had_errors = 0;
378 for (
unsigned int i = 0; i < 10; ++i)
380 status_data->motor_data_packet[i].torque = 4;
381 status_data->motor_data_packet[i].misc = 2 * i;
384 status_data->idle_time_us = 1;
387 lib_test->sr_hand_lib->update(status_data);
390 EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time, 1);
391 EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time_min, 1);
394 std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
395 for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
397 if (joint_tmp->has_actuator)
402 if (motor_wrapper->motor_id % 2 == 0)
404 const sr_actuator::SrMotorActuator *sr_actuator =
405 static_cast<sr_actuator::SrMotorActuator *
>(motor_wrapper->actuator);
407 ROS_ERROR_STREAM(
"last measured effort: " << sr_actuator->state_.last_measured_effort_ <<
" actuator: " <<
408 motor_wrapper->actuator);
410 EXPECT_FLOAT_EQ(sr_actuator->motor_state_.force_unfiltered_, 4.0);
411 EXPECT_EQ(sr_actuator->motor_state_.strain_gauge_right_, motor_wrapper->motor_id);
432 status_data->sensors[i] = i + 1;
438 status_data->which_motors = 0;
441 status_data->which_motor_data_arrived = 0x00055555;
442 status_data->which_motor_data_had_errors = 0;
445 for (
unsigned int i = 0; i < 10; ++i)
447 status_data->motor_data_packet[i].torque = i;
448 status_data->motor_data_packet[i].misc = 10 * i;
451 status_data->idle_time_us = 1;
454 lib_test->sr_hand_lib->update(status_data);
457 lib_test->check_hw_actuator(
"rh_FFJ4", 2, 3, 4.0);
680 std::vector<std::pair<std::string, bool> > flags;
682 flags = lib_test->sr_hand_lib->humanize_flags(0xFFFF);
684 EXPECT_EQ(flags.size(), 16);
686 for (
unsigned int i = 0; i < 16; ++i)
692 EXPECT_TRUE(flags[13].second);
693 EXPECT_TRUE(flags[14].second);
694 EXPECT_TRUE(flags[15].second);
701 int main(
int argc,
char **argv)
703 ros::init(argc, argv,
"calibration_test");
704 testing::InitGoogleTest(&argc, argv);
705 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)
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)
bool getParam(const std::string &key, std::string &s) const
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)