44 int main(
int argc,
char** argv)
46 ros::init(argc, argv,
"inverse_kinematics_test");
52 ROS_ERROR(
"An argument specifying the group name is needed");
56 std::string group = argv[1];
59 const robot_model::JointModelGroup* jmg = rml.
getModel()->getJointModelGroup(group);
62 const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
65 const std::string& tip = solver->getTipFrame();
66 robot_state::RobotState state(rml.
getModel());
67 state.setToDefaultValues();
74 unsigned int test_count = 1000;
78 test_count = boost::lexical_cast<
unsigned int>(argv[2]);
84 ROS_INFO(
"Running %u tests", test_count);
87 for (
unsigned int i = 0; i < test_count; ++i)
89 state.setToRandomPositions(jmg);
90 Eigen::Affine3d pose = state.getGlobalLinkTransform(tip);
91 state.setToRandomPositions(jmg);
93 state.setFromIK(jmg, pose);
95 const Eigen::Affine3d& pose_upd = state.getGlobalLinkTransform(tip);
96 Eigen::Affine3d
diff = pose_upd * pose.inverse(Eigen::Isometry);
97 double rot_err = (diff.linear() - Eigen::Matrix3d::Identity()).norm();
98 double trans_err = diff.translation().norm();
101 if (rot_err < 1e-3 && trans_err < 1e-3)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
int main(int argc, char **argv)
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void shutdown()
const robot_model::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
#define ROS_ERROR_STREAM(args)
static const std::string ROBOT_DESCRIPTION