62 auto start_time = std::chrono::system_clock::now();
66 RCLCPP_ERROR(getLogger(),
"No planning scene initialized.");
67 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
77 RCLCPP_ERROR(getLogger(),
"Start state violates joint limits");
78 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
85 if (req.goal_constraints.size() != 1)
87 RCLCPP_ERROR(getLogger(),
"Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
88 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
92 if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
93 !req.goal_constraints[0].orientation_constraints.empty())
95 RCLCPP_ERROR(getLogger(),
"Only joint-space goals are supported");
96 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
100 const size_t goal_index = trajectory.
getNumPoints() - 1;
102 for (
const moveit_msgs::msg::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
106 RCLCPP_ERROR(getLogger(),
"Goal state violates joint limits");
107 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
110 robotStateToArray(goal_state, req.group_name, trajectory.
getTrajectoryPoint(goal_index));
113 planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
121 if (revolute_joint !=
nullptr)
125 double start = (trajectory)(0, i);
126 double end = (trajectory)(goal_index, i);
127 RCLCPP_INFO(getLogger(),
"Start is %f end %f short %f", start, end, shortestAngularDistance(start, end));
128 (trajectory)(goal_index, i) = start + shortestAngularDistance(start, end);
150 RCLCPP_ERROR(getLogger(),
"No input trajectory specified");
155 RCLCPP_ERROR(getLogger(),
"Input trajectory has less than 2 points, "
156 "trajectory must contain at least start and goal state");
162 RCLCPP_ERROR(getLogger(),
"invalid interpolation method specified in the chomp_planner file");
166 RCLCPP_INFO(getLogger(),
"CHOMP trajectory initialized using method: %s ",
170 auto create_time = std::chrono::system_clock::now();
172 int replan_count = 0;
173 bool replan_flag =
false;
174 double org_learning_rate = 0.04, org_ridge_factor = 0.0, org_planning_time_limit = 10;
175 int org_max_iterations = 200;
183 std::unique_ptr<ChompOptimizer> optimizer;
202 std::make_unique<ChompOptimizer>(&trajectory,
planning_scene, req.group_name, ¶ms_nonconst, start_state);
203 if (!optimizer->isInitialized())
205 RCLCPP_ERROR(getLogger(),
"Could not initialize optimizer");
206 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
210 RCLCPP_DEBUG(getLogger(),
"Optimization took %ld sec to create",
211 (std::chrono::system_clock::now() - create_time).count());
213 bool optimization_result = optimizer->optimize();
218 RCLCPP_INFO(getLogger(),
219 "Planned with Chomp Parameters (learning_rate, ridge_factor, "
220 "planning_time_limit, max_iterations), attempt: # %d ",
222 RCLCPP_INFO(getLogger(),
"Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
241 params_nonconst.
setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
243 RCLCPP_DEBUG(getLogger(),
"Optimization actually took %ld sec to run",
244 (std::chrono::system_clock::now() - create_time).count());
245 create_time = std::chrono::system_clock::now();
248 RCLCPP_DEBUG(getLogger(),
"Output trajectory has %zd joints", trajectory.
getNumJoints());
250 auto result = std::make_shared<robot_trajectory::RobotTrajectory>(
planning_scene->getRobotModel(), req.group_name);
255 auto state = std::make_shared<moveit::core::RobotState>(start_state);
256 size_t joint_index = 0;
259 assert(jm->getVariableCount() == 1);
260 state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
262 result->addSuffixWayPoint(state, 0.0);
270 RCLCPP_DEBUG(getLogger(),
"Bottom took %ld sec to create", (std::chrono::system_clock::now() - create_time).count());
271 RCLCPP_DEBUG(getLogger(),
"Serviced planning request in %ld wall-seconds",
272 (std::chrono::system_clock::now() - start_time).count());
274 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
276 res.
processing_time[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
279 if (not optimizer->isCollisionFree())
281 RCLCPP_ERROR(getLogger(),
"Motion plan is invalid.");
282 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
289 for (
const moveit_msgs::msg::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
293 RCLCPP_ERROR(getLogger(),
"Goal constraints are violated: %s", constraint.joint_name.c_str());
294 res.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;
300 res.
processing_time[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();