Go to the documentation of this file.
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];
65 const std::string& tip = solver->getTipFrame();
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)
98 Eigen::Isometry3d diff = pose_upd * pose.inverse();
99 double rot_err = (diff.linear() - Eigen::Matrix3d::Identity()).norm();
100 double trans_err = diff.translation().norm();
103 if (rot_err < 1e-3 && trans_err < 1e-3)
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
static const std::string ROBOT_DESCRIPTION
ROSCPP_DECL void shutdown()
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
bool setFromIK(const JointModelGroup *group, const geometry_msgs::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
void setToRandomPositions()
const kinematics::KinematicsBasePtr & getSolverInstance()
void setToDefaultValues()
#define ROS_INFO_STREAM(args)
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Thu Feb 27 2025 03:27:54