test_constraint_aware_kinematics.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sachin Chitta */
36 
37 #include <ros/ros.h>
38 #include <gtest/gtest.h>
40 
41 // MoveIt!
45 #include <moveit/robot_state/joint_state_group.h>
50 #include <urdf/model.h>
51 #include <srdfdom/model.h>
52 
53 TEST(ConstraintAwareKinematics, getIK)
54 {
55  std::string group_name = "right_arm";
56  std::string ik_link_name = "r_wrist_roll_link";
57 
58  ROS_INFO("Initializing IK solver");
59  planning_scene::PlanningScenePtr planning_scene;
61  robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
62 
63  const srdf::ModelSharedPtr& srdf = robot_model_loader.getSRDF();
64  const urdf::ModelInterfaceSharedPtr& urdf_model = robot_model_loader.getURDF();
65 
66  planning_scene.reset(new planning_scene::PlanningScene(kinematic_model));
67 
68  const robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(group_name);
69 
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();
73 
74  kinematics_constraint_aware::KinematicsConstraintAware solver(kinematic_model, "right_arm");
75 
76  ros::NodeHandle nh("~");
77  int number_ik_tests;
78  nh.param("number_ik_tests", number_ik_tests, 1);
79 
80  int acceptable_success_percentage;
81  nh.param("accepatable_success_percentage", acceptable_success_percentage, 95);
82 
83  unsigned int num_success = 0;
84 
87  kinematics_response.solution_.reset(new robot_state::RobotState(planning_scene->getCurrentState()));
88 
89  kinematics_request.group_name_ = group_name;
90  kinematics_request.timeout_ = ros::Duration(5.0);
91  kinematics_request.check_for_collisions_ = false;
92  kinematics_request.robot_state_ = kinematic_state;
93 
94  geometry_msgs::PoseStamped goal;
95  goal.header.frame_id = kinematic_model->getModelFrame();
96 
97  for(std::size_t i = 0; i < (unsigned int) number_ik_tests; ++i)
98  {
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();
110 
111  joint_state_group->setToRandomValues();
112  kinematics_request.pose_stamped_vector_.clear();
113  kinematics_request.pose_stamped_vector_.push_back(goal);
115  if(solver.getIK(planning_scene, kinematics_request, kinematics_response))
116  num_success++;
117  else
118  printf("Failed in %f\n", (ros::WallTime::now()-start).toSec());
119  }
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);
122  EXPECT_TRUE(test_success);
123 }
124 
125 
126 int main(int argc, char **argv)
127 {
128  testing::InitGoogleTest(&argc, argv);
129  ros::init (argc, argv, "right_arm_kinematics");
130  return RUN_ALL_TESTS();
131 }
const srdf::ModelSharedPtr & getSRDF() const
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
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_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
static WallTime now()
TEST(ConstraintAwareKinematics, getIK)
const robot_model::RobotModelPtr & getModel() const
#define EXPECT_TRUE(args)


pr2_moveit_tests
Author(s): Sachin Chitta
autogenerated on Sun Nov 17 2019 03:24:53