38 #include <gtest/gtest.h> 50 #define IK_NEAR_TRANSLATE 1e-5 57 double search_discretization;
60 std::string plugin_name;
61 if (!nh.
getParam(
"plugin_name", plugin_name))
63 ROS_ERROR(
"No plugin name found on parameter server");
67 ROS_INFO(
"Plugin name: %s",plugin_name.c_str());
74 ROS_ERROR(
"The plugin failed to load. Error: %s", ex.what());
78 std::string root_name, tip_name;
83 if (!nh.
getParam(
"root_name", root_name))
85 ROS_ERROR(
"No root name found on parameter server");
90 if (!nh.
getParam(
"tip_name", tip_name))
92 ROS_ERROR(
"No tip name found on parameter server");
97 if (!nh.
getParam(
"search_discretization", search_discretization))
99 ROS_ERROR(
"No search discretization found on parameter server");
110 if(
kinematics_solver_->initialize(
"robot_description",
"right_arm",root_name,tip_name,search_discretization))
121 const std::vector<double> &joint_state,
122 moveit_msgs::MoveItErrorCodes &error_code)
124 std::vector<std::string> link_names;
125 link_names.push_back(
"r_elbow_flex_link");
126 std::vector<geometry_msgs::Pose> solutions;
129 error_code.val = error_code.PLANNING_FAILED;
130 if(solutions[0].position.z > 0.0)
131 error_code.val = error_code.SUCCESS;
133 error_code.val = error_code.PLANNING_FAILED;
147 EXPECT_TRUE(root_name == std::string(
"torso_lift_link"));
149 EXPECT_TRUE(tool_name == std::string(
"r_wrist_roll_link"));
153 EXPECT_EQ(joint_names[0],
"r_shoulder_pan_joint");
154 EXPECT_EQ(joint_names[1],
"r_shoulder_lift_joint");
155 EXPECT_EQ(joint_names[2],
"r_upper_arm_roll_joint");
156 EXPECT_EQ(joint_names[3],
"r_elbow_flex_joint");
157 EXPECT_EQ(joint_names[4],
"r_forearm_roll_joint");
158 EXPECT_EQ(joint_names[5],
"r_wrist_flex_joint");
159 EXPECT_EQ(joint_names[6],
"r_wrist_roll_joint");
165 robot_model::RobotModelPtr kinematic_model;
167 const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader_.
getURDF();
168 kinematic_model.reset(
new robot_model::RobotModel(urdf_model, srdf));
169 robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.
kinematics_solver_->getGroupName());
171 std::vector<double> seed, fk_values, solution;
172 moveit_msgs::MoveItErrorCodes error_code;
175 std::vector<std::string> fk_names;
178 robot_state::RobotState kinematic_state(kinematic_model);
182 nh.
param(
"number_fk_tests", number_fk_tests, 100);
184 for(
unsigned int i=0; i < (
unsigned int) number_fk_tests; ++i)
189 kinematic_state.setToRandomPositions(joint_model_group);
190 kinematic_state.copyJointGroupPositions(joint_model_group, fk_values);
192 std::vector<geometry_msgs::Pose> poses;
194 bool result_fk = my_test.
kinematics_solver_->getPositionFK(fk_names, fk_values, poses);
195 ASSERT_TRUE(result_fk);
202 robot_model::RobotModelPtr kinematic_model;
204 const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader_.
getURDF();
205 kinematic_model.reset(
new robot_model::RobotModel(urdf_model, srdf_model));
206 robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.
kinematics_solver_->getGroupName());
209 std::vector<double> seed, fk_values, solution;
210 double timeout = 5.0;
211 moveit_msgs::MoveItErrorCodes error_code;
214 std::vector<std::string> fk_names;
217 robot_state::RobotState kinematic_state(kinematic_model);
222 nh.
param(
"number_ik_tests", number_ik_tests, 10);
223 unsigned int success = 0;
226 for(
unsigned int i=0; i < (
unsigned int) number_ik_tests; ++i)
231 kinematic_state.setToRandomPositions(joint_model_group);
232 kinematic_state.copyJointGroupPositions(joint_model_group, fk_values);
234 std::vector<geometry_msgs::Pose> poses;
236 bool result_fk = my_test.
kinematics_solver_->getPositionFK(fk_names, fk_values, poses);
237 ASSERT_TRUE(result_fk);
239 bool result = my_test.
kinematics_solver_->searchPositionIK(poses[0], seed, timeout, solution, error_code);
240 ROS_DEBUG(
"Pose: %f %f %f",poses[0].position.x, poses[0].position.y, poses[0].position.z);
241 ROS_DEBUG(
"Orient: %f %f %f %f",poses[0].orientation.x, poses[0].orientation.y, poses[0].orientation.z, poses[0].orientation.w);
245 result = my_test.
kinematics_solver_->getPositionIK(poses[0], solution, solution, error_code);
249 std::vector<geometry_msgs::Pose> new_poses;
262 ROS_INFO(
"Success Rate: %f",(
double)success/number_ik_tests);
263 bool success_count = (success > 0.99 * number_ik_tests);
268 TEST(ArmIKPlugin, searchIKWithCallbacks)
271 robot_model::RobotModelPtr kinematic_model;
273 const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader_.
getURDF();
274 kinematic_model.reset(
new robot_model::RobotModel(urdf_model, srdf));
275 robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.
kinematics_solver_->getGroupName());
278 std::vector<double> seed,fk_values,solution;
279 double timeout = 5.0;
280 moveit_msgs::MoveItErrorCodes error_code;
283 std::vector<std::string> fk_names;
286 robot_state::RobotState kinematic_state(kinematic_model);
291 nh.
param(
"number_ik_tests_with_callbacks", number_ik_tests, 10);
292 unsigned int success = 0;
293 unsigned int num_actual_tests = 0;
295 for(
unsigned int i=0; i < (
unsigned int) number_ik_tests; ++i)
300 kinematic_state.setToRandomPositions(joint_model_group);
301 kinematic_state.copyJointGroupPositions(joint_model_group, fk_values);
303 std::vector<geometry_msgs::Pose> poses;
305 bool result_fk = my_test.
kinematics_solver_->getPositionFK(fk_names, fk_values, poses);
306 ASSERT_TRUE(result_fk);
307 if(poses[0].position.z < 0.0)
311 bool result = my_test.
kinematics_solver_->searchPositionIK(poses[0], seed, timeout, solution,
317 std::vector<geometry_msgs::Pose> new_poses;
334 ROS_INFO(
"Success with callbacks (%%): %f",(
double)success/num_actual_tests*100.0);
338 int main(
int argc,
char **argv)
340 testing::InitGoogleTest(&argc, argv);
341 ros::init (argc, argv,
"right_arm_kinematics");
342 return RUN_ALL_TESTS();
std::shared_ptr< pluginlib::ClassLoader< kinematics::KinematicsBase > > kinematics_loader_
const srdf::ModelSharedPtr & getSRDF() const
boost::shared_ptr< kinematics::KinematicsBase > kinematics_solver_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define EXPECT_NEAR(a, b, prec)
void joint_state_callback(const geometry_msgs::Pose &ik_pose, const std::vector< double > &joint_state, moveit_msgs::MoveItErrorCodes &error_code)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TEST(ArmIKPlugin, initialize)
int main(int argc, char **argv)
bool getParam(const std::string &key, std::string &s) const
#define EXPECT_TRUE(args)
const urdf::ModelInterfaceSharedPtr & getURDF() const