38 #include <rclcpp/rclcpp.hpp>
39 #include <boost/program_options.hpp>
44 namespace po = boost::program_options;
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"cached_ik.measure_ik_call_cost");
49 int main(
int argc,
char* argv[])
54 bool reset_to_default;
55 po::options_description desc(
"Options");
58 (
"help",
"show help message")
59 (
"group", po::value<std::string>(&
group)->default_value(
"all"),
"name of planning group")
60 (
"tip", po::value<std::string>(&tip)->default_value(
"default"),
"name of the end effector in the planning group")
61 (
"num", po::value<unsigned int>(&num)->default_value(100000),
"number of IK solutions to compute")
62 (
"reset_to_default", po::value<bool>(&reset_to_default)->default_value(
true),
63 "whether to reset IK seed to default state. If set to false, the seed is the "
64 "correct IK solution (to accelerate filling the cache).");
68 po::store(po::parse_command_line(argc, argv, desc), vm);
71 if (vm.count(
"help") != 0u)
73 std::cout << desc <<
"\n";
77 rclcpp::init(argc, argv);
78 rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"benchmark_ik");
79 rclcpp::executors::MultiThreadedExecutor executor;
80 executor.add_node(node);
90 std::chrono::duration<double> ik_time(0);
91 std::chrono::time_point<std::chrono::system_clock> start;
92 std::vector<moveit::core::JointModelGroup*> groups;
93 std::vector<std::string> end_effectors;
96 groups = kinematic_model->getJointModelGroups();
98 groups.push_back(kinematic_model->getJointModelGroup(
group));
100 for (
const auto&
group : groups)
103 if (
group->getSolverInstance() ==
nullptr)
105 RCLCPP_WARN_STREAM(LOGGER,
"No kinematic solver configured for group '" <<
group->getName() <<
"' - skipping");
109 if (tip ==
"default")
110 group->getEndEffectorTips(end_effectors);
112 end_effectors = std::vector<std::string>(1, tip);
117 EigenSTL::vector_Isometry3d default_eef_states;
118 for (
const auto& end_effector : end_effectors)
120 if (end_effectors.size() == 1)
121 kinematic_state.
setFromIK(
group, default_eef_states[0], end_effectors[0], 0.1);
123 kinematic_state.
setFromIK(
group, default_eef_states, end_effectors, 0.1);
126 unsigned int num_failed_calls = 0, num_self_collisions = 0;
127 EigenSTL::vector_Isometry3d end_effector_states(end_effectors.size());
132 collision_result.
clear();
133 planning_scene.checkSelfCollision(collision_request, collision_result);
136 ++num_self_collisions;
139 for (
unsigned j = 0; j < end_effectors.size(); ++j)
141 if (reset_to_default)
143 start = std::chrono::system_clock::now();
144 if (end_effectors.size() == 1)
145 found_ik = kinematic_state.
setFromIK(
group, end_effector_states[0], end_effectors[0], 0.1);
147 found_ik = kinematic_state.
setFromIK(
group, end_effector_states, end_effectors, 0.1);
148 ik_time += std::chrono::system_clock::now() - start;
154 "Avg. time per IK solver call is %g after %d calls. %g%% of calls failed to return a solution. "
155 "%g%% of random joint configurations were ignored due to self-collisions.",
156 ik_time.count() / (
double)i, i, 100. * num_failed_calls / i,
157 100. * num_self_collisions / (num_self_collisions + i));
159 RCLCPP_INFO(LOGGER,
"Summary for group %s: %g %g %g",
group->getName().c_str(), ik_time.count() / (
double)i,
160 100. * num_failed_calls / i, 100. * num_self_collisions / (num_self_collisions + i));
int main(int argc, char *argv[])
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
This class maintains the representation of the environment as seen by a planning instance....
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
This namespace includes the central class for representing planning contexts.
Representation of a collision checking request.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.