Skip to content

Commit

Permalink
Cleanup and switch to getMinJointDisplacementCostFn
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Sep 14, 2023
1 parent 03b7a7f commit 298e115
Showing 1 changed file with 2 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -263,9 +263,8 @@ class Demo
{
planning_component_->setStateCostFunction(
[robot_start_state, group_name, planning_scene](const Eigen::VectorXd& state_vector) mutable {
// rviz_visual_tools::MEDIUM); this->getVisualTools().trigger();
auto clearance_cost_fn =
moveit::cost_functions::getClearanceCostFn(*robot_start_state, group_name, planning_scene);
moveit::cost_functions::getMinJointDisplacementCostFn(*robot_start_state, group_name, planning_scene);
return clearance_cost_fn(state_vector);
});
}
Expand All @@ -286,8 +285,7 @@ class Demo
if (plan_solution.trajectory)
{
RCLCPP_INFO_STREAM(LOGGER, plan_solution.planner_id.c_str()
<< ", " << std::to_string(plan_solution.use_cost_function) << ": "
<< colorToString(rviz_visual_tools::Colors(color_index)));
<< ": " << colorToString(rviz_visual_tools::Colors(color_index)));
// Visualize the trajectory in Rviz
visual_tools_.publishTrajectoryLine(plan_solution.trajectory, joint_model_group_ptr,
rviz_visual_tools::Colors(color_index));
Expand Down

0 comments on commit 298e115

Please sign in to comment.