67  auto start_time = std::chrono::system_clock::now();
 
   71    RCLCPP_ERROR(getLogger(), 
"No planning scene initialized.");
 
   72    res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
   82    RCLCPP_ERROR(getLogger(), 
"Start state violates joint limits");
 
   83    res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
 
   90  if (req.goal_constraints.size() != 1)
 
   92    RCLCPP_ERROR(getLogger(), 
"Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
 
   93    res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
 
   97  if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
 
   98      !req.goal_constraints[0].orientation_constraints.empty())
 
  100    RCLCPP_ERROR(getLogger(), 
"Only joint-space goals are supported");
 
  101    res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
 
  105  const size_t goal_index = trajectory.
getNumPoints() - 1;
 
  107  for (
const moveit_msgs::msg::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
 
  111    RCLCPP_ERROR(getLogger(), 
"Goal state violates joint limits");
 
  112    res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
 
  115  robotStateToArray(goal_state, req.group_name, trajectory.
getTrajectoryPoint(goal_index));
 
  118      planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
 
  126    if (revolute_joint != 
nullptr)
 
  130        double start = (trajectory)(0, i);
 
  131        double end = (trajectory)(goal_index, i);
 
  132        RCLCPP_INFO(getLogger(), 
"Start is %f end %f short %f", start, end, shortestAngularDistance(start, end));
 
  133        (trajectory)(goal_index, i) = start + shortestAngularDistance(start, end);
 
  155      RCLCPP_ERROR(getLogger(), 
"No input trajectory specified");
 
  160      RCLCPP_ERROR(getLogger(), 
"Input trajectory has less than 2 points, " 
  161                                "trajectory must contain at least start and goal state");
 
  167    RCLCPP_ERROR(getLogger(), 
"invalid interpolation method specified in the chomp_planner file");
 
  171  RCLCPP_INFO(getLogger(), 
"CHOMP trajectory initialized using method: %s ",
 
  175  auto create_time = std::chrono::system_clock::now();
 
  177  int replan_count = 0;
 
  178  bool replan_flag = 
false;
 
  179  double org_learning_rate = 0.04, org_ridge_factor = 0.0, org_planning_time_limit = 10;
 
  180  int org_max_iterations = 200;
 
  188  std::unique_ptr<ChompOptimizer> optimizer;
 
  207        std::make_unique<ChompOptimizer>(&trajectory, 
planning_scene, req.group_name, ¶ms_nonconst, start_state);
 
  208    if (!optimizer->isInitialized())
 
  210      RCLCPP_ERROR(getLogger(), 
"Could not initialize optimizer");
 
  211      res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
 
  215    RCLCPP_DEBUG(getLogger(), 
"Optimization took %ld sec to create",
 
  216                 (std::chrono::system_clock::now() - create_time).count());
 
  218    bool optimization_result = optimizer->optimize();
 
  223      RCLCPP_INFO(getLogger(),
 
  224                  "Planned with Chomp Parameters (learning_rate, ridge_factor, " 
  225                  "planning_time_limit, max_iterations), attempt: # %d ",
 
  227      RCLCPP_INFO(getLogger(), 
"Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
 
  246  params_nonconst.
setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
 
  248  RCLCPP_DEBUG(getLogger(), 
"Optimization actually took %ld sec to run",
 
  249               (std::chrono::system_clock::now() - create_time).count());
 
  250  create_time = std::chrono::system_clock::now();
 
  253  RCLCPP_DEBUG(getLogger(), 
"Output trajectory has %zd joints", trajectory.
getNumJoints());
 
  255  auto result = std::make_shared<robot_trajectory::RobotTrajectory>(
planning_scene->getRobotModel(), req.group_name);
 
  260    auto state = std::make_shared<moveit::core::RobotState>(start_state);
 
  261    size_t joint_index = 0;
 
  264      assert(jm->getVariableCount() == 1);
 
  265      state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
 
  267    result->addSuffixWayPoint(state, 0.0);
 
  275  RCLCPP_DEBUG(getLogger(), 
"Bottom took %ld sec to create", (std::chrono::system_clock::now() - create_time).count());
 
  276  RCLCPP_DEBUG(getLogger(), 
"Serviced planning request in %ld wall-seconds",
 
  277               (std::chrono::system_clock::now() - start_time).count());
 
  279  res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  281  res.
processing_time[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
 
  284  if (!optimizer->isCollisionFree())
 
  286    RCLCPP_ERROR(getLogger(), 
"Motion plan is invalid.");
 
  287    res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
 
  294  for (
const moveit_msgs::msg::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
 
  298      RCLCPP_ERROR(getLogger(), 
"Goal constraints are violated: %s", constraint.joint_name.c_str());
 
  299      res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;
 
  305  res.
processing_time[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();