kinematics_speed_and_validity_evaluator.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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: Ioan Sucan */
36 
40 #include <ros/ros.h>
41 
42 static const std::string ROBOT_DESCRIPTION = "robot_description";
43 
44 int main(int argc, char** argv)
45 {
46  ros::init(argc, argv, "inverse_kinematics_test");
47 
49  spinner.start();
50 
51  if (argc <= 1)
52  ROS_ERROR("An argument specifying the group name is needed");
53  else
54  {
56  std::string group = argv[1];
57  ROS_INFO_STREAM("Evaluating IK for " << group);
58 
59  const moveit::core::JointModelGroup* jmg = rml.getModel()->getJointModelGroup(group);
60  if (jmg)
61  {
62  const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
63  if (solver)
64  {
65  const std::string& tip = solver->getTipFrame();
67  state.setToDefaultValues();
68 
69  ROS_INFO_STREAM("Tip Frame: " << solver->getTipFrame());
70  ROS_INFO_STREAM("Base Frame: " << solver->getBaseFrame());
71  ROS_INFO_STREAM("IK Timeout: " << solver->getDefaultTimeout());
72  ROS_INFO_STREAM("Search res: " << solver->getSearchDiscretization());
73 
74  unsigned int test_count = 1000;
75  if (argc > 2)
76  try
77  {
78  test_count = boost::lexical_cast<unsigned int>(argv[2]);
79  }
80  catch (...)
81  {
82  }
83 
84  ROS_INFO("Running %u tests", test_count);
85 
87  for (unsigned int i = 0; i < test_count; ++i)
88  {
89  state.setToRandomPositions(jmg);
90  // getGlobalLinkTransform() returns a valid isometry by contract
91  Eigen::Isometry3d pose = state.getGlobalLinkTransform(tip);
92  state.setToRandomPositions(jmg);
94  state.setFromIK(jmg, pose);
96  // getGlobalLinkTransform() returns a valid isometry by contract
97  const Eigen::Isometry3d& pose_upd = state.getGlobalLinkTransform(tip);
98  Eigen::Isometry3d diff = pose_upd * pose.inverse(); // valid isometry
99  double rot_err = (diff.linear() - Eigen::Matrix3d::Identity()).norm();
100  double trans_err = diff.translation().norm();
101  moveit::tools::Profiler::Average("Rotation error", rot_err);
102  moveit::tools::Profiler::Average("Translation error", trans_err);
103  if (rot_err < 1e-3 && trans_err < 1e-3)
104  {
105  moveit::tools::Profiler::Event("Valid IK");
106  moveit::tools::Profiler::Average("Success Rate", 100);
107  }
108  else
109  {
110  moveit::tools::Profiler::Event("Invalid IK");
111  moveit::tools::Profiler::Average("Success Rate", 0);
112  }
113  }
116  }
117  else
118  ROS_ERROR_STREAM("No kinematics solver specified for group " << group);
119  }
120  }
121 
122  ros::shutdown();
123  return 0;
124 }
moveit::tools::Profiler::Status
static void Status(std::ostream &out=std::cout, bool merge=true)
moveit::tools::Profiler::Begin
static void Begin(const std::string &name)
moveit::tools::Profiler::Average
static void Average(const std::string &name, const double value)
main
int main(int argc, char **argv)
Definition: kinematics_speed_and_validity_evaluator.cpp:44
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ros::AsyncSpinner
ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: kinematics_speed_and_validity_evaluator.cpp:42
ros::shutdown
ROSCPP_DECL void shutdown()
robot_model_loader::RobotModelLoader
Definition: robot_model_loader.h:80
moveit::tools::Profiler::Stop
static void Stop()
moveit::core::RobotState
moveit::core::RobotState::getGlobalLinkTransform
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
moveit::core::RobotState::setFromIK
bool setFromIK(const JointModelGroup *group, const geometry_msgs::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
moveit::core::RobotState::setToRandomPositions
void setToRandomPositions()
robot_state.h
spinner
void spinner()
moveit::core::JointModelGroup::getSolverInstance
const kinematics::KinematicsBasePtr & getSolverInstance()
moveit::tools::Profiler::Start
static void Start()
moveit::core::RobotState::setToDefaultValues
void setToDefaultValues()
ROS_ERROR
#define ROS_ERROR(...)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
moveit::core::JointModelGroup
moveit::tools::Profiler::End
static void End(const std::string &name)
profiler.h
ROS_INFO
#define ROS_INFO(...)
moveit::tools::Profiler::Event
static void Event(const std::string &name, const unsigned int times=1)
robot_model_loader::RobotModelLoader::getModel
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
Definition: robot_model_loader.h:118
robot_model_loader.h


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:27:54