38 #include <gtest/gtest.h> 45 #include <moveit/robot_state/joint_state_group.h> 53 TEST(ConstraintAwareKinematics, getIK)
55 std::string group_name =
"right_arm";
56 std::string ik_link_name =
"r_wrist_roll_link";
61 robot_model::RobotModelPtr kinematic_model = robot_model_loader.
getModel();
64 const urdf::ModelInterfaceSharedPtr& urdf_model = robot_model_loader.
getURDF();
68 const robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(group_name);
70 robot_state::RobotStatePtr kinematic_state(
new robot_state::RobotState(kinematic_model));
71 robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup(group_name);
72 kinematic_state->setToDefaultValues();
78 nh.
param(
"number_ik_tests", number_ik_tests, 1);
80 int acceptable_success_percentage;
81 nh.
param(
"accepatable_success_percentage", acceptable_success_percentage, 95);
83 unsigned int num_success = 0;
87 kinematics_response.
solution_.reset(
new robot_state::RobotState(planning_scene->getCurrentState()));
94 geometry_msgs::PoseStamped goal;
95 goal.header.frame_id = kinematic_model->getModelFrame();
97 for(std::size_t i = 0; i < (
unsigned int) number_ik_tests; ++i)
99 joint_state_group->setToRandomValues();
100 const Eigen::Affine3d &end_effector_state = joint_state_group->getRobotState()->getLinkState(ik_link_name)->getGlobalLinkTransform();
101 Eigen::Quaterniond quat(end_effector_state.rotation());
102 Eigen::Vector3d point(end_effector_state.translation());
103 goal.pose.position.x = point.x();
104 goal.pose.position.y = point.y();
105 goal.pose.position.z = point.z();
106 goal.pose.orientation.x = quat.x();
107 goal.pose.orientation.y = quat.y();
108 goal.pose.orientation.z = quat.z();
109 goal.pose.orientation.w = quat.w();
111 joint_state_group->setToRandomValues();
115 if(solver.
getIK(planning_scene, kinematics_request, kinematics_response))
120 bool test_success = (((double)num_success)/number_ik_tests > acceptable_success_percentage/100.0);
121 printf(
"success ratio: %d of %d", num_success, number_ik_tests);
126 int main(
int argc,
char **argv)
128 testing::InitGoogleTest(&argc, argv);
129 ros::init (argc, argv,
"right_arm_kinematics");
130 return RUN_ALL_TESTS();
robot_state::RobotStatePtr solution_
const srdf::ModelSharedPtr & getSRDF() const
bool check_for_collisions_
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< geometry_msgs::PoseStamped > pose_stamped_vector_
const urdf::ModelInterfaceSharedPtr & getURDF() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
robot_state::RobotStatePtr robot_state_
TEST(ConstraintAwareKinematics, getIK)
const robot_model::RobotModelPtr & getModel() const
#define EXPECT_TRUE(args)