@@ -297,6 +297,17 @@ class Demo
297297 << " max_velocity_scaling_factor: " << plan_request_parameters.max_velocity_scaling_factor << ' ,'
298298 << " max_acceleration_scaling_factor: " << plan_request_parameters.max_acceleration_scaling_factor );
299299
300+ // planning_component_->setStateCostFunction(
301+ // [robot_start_state, group_name, planning_scene](const std::vector<double>& state_vector) mutable {
302+ // // Publish robot state
303+ // // auto const ee_tip = robot_state.getJointModelGroup(PLANNING_GROUP)->getOnlyOneEndEffectorTip();
304+ // // this->getVisualTools().publishSphere(robot_state.getGlobalLinkTransform(ee_tip), rviz_visual_tools::GREEN,
305+ // // rviz_visual_tools::MEDIUM); this->getVisualTools().trigger();
306+ // auto clearance_cost_fn =
307+ // moveit::cost_functions::getClearanceCostFn(*robot_start_state, group_name, planning_scene);
308+ // return clearance_cost_fn(state_vector);
309+ // });
310+
300311 std::vector<planning_interface::MotionPlanResponse> solutions;
301312 solutions.reserve (pipeline_planner_pairs.size ());
302313 for (auto const & pipeline_planner_pair : pipeline_planner_pairs)
@@ -310,18 +321,18 @@ class Demo
310321 auto robot_model_ptr = moveit_cpp_->getRobotModel ();
311322 auto joint_model_group_ptr = robot_model_ptr->getJointModelGroup (PLANNING_GROUP);
312323 // Check if PlanningComponents succeeded in finding the plan
313- for (auto const & plan_solution : solutions)
314- {
315- if (plan_solution.trajectory )
316- {
317- RCLCPP_INFO_STREAM (LOGGER, plan_solution.planner_id .c_str ()
318- << " : " << colorToString (rviz_visual_tools::Colors (color_index)));
319- // Visualize the trajectory in Rviz
320- visual_tools_.publishTrajectoryLine (plan_solution.trajectory , joint_model_group_ptr,
321- rviz_visual_tools::Colors (color_index));
322- color_index++;
323- }
324- }
324+ // for (auto const& plan_solution : solutions)
325+ // {
326+ // if (plan_solution.trajectory)
327+ // {
328+ // RCLCPP_INFO_STREAM(LOGGER, plan_solution.planner_id.c_str()
329+ // << ": " << colorToString(rviz_visual_tools::Colors(color_index)));
330+ // // Visualize the trajectory in Rviz
331+ // visual_tools_.publishTrajectoryLine(plan_solution.trajectory, joint_model_group_ptr,
332+ // rviz_visual_tools::Colors(color_index));
333+ // color_index++;
334+ // }
335+ // }
325336 visual_tools_.trigger ();
326337 }
327338
@@ -367,7 +378,7 @@ int main(int argc, char** argv)
367378 demo.setQueryGoal ();
368379
369380 demo.planAndVisualize (
370- { { " ompl " , " RRTConnectkConfigDefault" }, { " ompl" , " RRTstarkConfigDefault" }, { " stomp" , " stomp" } });
381+ { { " ompl_stomp " , " RRTConnectkConfigDefault" }, /* { "ompl", "RRTstarkConfigDefault" }, { "stomp", "stomp" }*/ });
371382
372383 demo.getVisualTools ().prompt (" Press 'next' in the RvizVisualToolsGui window to finish the demo" );
373384 rclcpp::shutdown ();
0 commit comments