42 #include <moveit_msgs/MotionPlanRequest.h>
54 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
65 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE;
69 ChompTrajectory trajectory(
planning_scene->getRobotModel(), 3.0, .03, req.group_name);
72 if (req.goal_constraints.size() != 1)
74 ROS_ERROR_NAMED(
"chomp_planner",
"Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
75 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
79 if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
80 !req.goal_constraints[0].orientation_constraints.empty())
83 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
87 const size_t goal_index = trajectory.getNumPoints() - 1;
89 for (
const moveit_msgs::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
90 goal_state.setVariablePosition(joint_constraint.joint_name, joint_constraint.position);
91 if (!goal_state.satisfiesBounds())
94 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE;
97 robotStateToArray(goal_state, req.group_name, trajectory.getTrajectoryPoint(goal_index));
100 planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
108 if (revolute_joint !=
nullptr)
112 double start = (trajectory)(0, i);
113 double end = (trajectory)(goal_index, i);
121 if (params.trajectory_initialization_method_.compare(
"quintic-spline") == 0)
122 trajectory.fillInMinJerk();
123 else if (params.trajectory_initialization_method_.compare(
"linear") == 0)
124 trajectory.fillInLinearInterpolation();
125 else if (params.trajectory_initialization_method_.compare(
"cubic") == 0)
126 trajectory.fillInCubicInterpolation();
127 else if (params.trajectory_initialization_method_.compare(
"fillTrajectory") == 0)
134 else if (!(trajectory.fillInFromTrajectory(*res.
trajectory_[0])))
137 "trajectory must contain at least start and goal state");
143 ROS_ERROR_STREAM_NAMED(
"chomp_planner",
"invalid interpolation method specified in the chomp_planner file");
147 ROS_INFO_NAMED(
"chomp_planner",
"CHOMP trajectory initialized using method: %s ",
148 (params.trajectory_initialization_method_).c_str());
153 int replan_count = 0;
154 bool replan_flag =
false;
155 double org_learning_rate = 0.04, org_ridge_factor = 0.0, org_planning_time_limit = 10;
156 int org_max_iterations = 200;
159 org_learning_rate = params.learning_rate_;
160 org_ridge_factor = params.ridge_factor_;
161 org_planning_time_limit = params.planning_time_limit_;
162 org_max_iterations = params.max_iterations_;
164 std::unique_ptr<ChompOptimizer> optimizer;
167 ChompParameters params_nonconst = params;
176 params_nonconst.setRecoveryParams(params_nonconst.learning_rate_ + 0.02, params_nonconst.ridge_factor_ + 0.002,
177 params_nonconst.planning_time_limit_ + 5, params_nonconst.max_iterations_ + 50);
183 std::make_unique<ChompOptimizer>(&trajectory,
planning_scene, req.group_name, ¶ms_nonconst, start_state);
184 if (!optimizer->isInitialized())
187 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
193 bool optimization_result = optimizer->optimize();
196 if (params_nonconst.enable_failure_recovery_)
199 "Planned with Chomp Parameters (learning_rate, ridge_factor, "
200 "planning_time_limit, max_iterations), attempt: # %d ",
202 ROS_INFO_NAMED(
"chomp_planner",
"Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
203 params_nonconst.learning_rate_, params_nonconst.ridge_factor_,
204 params_nonconst.planning_time_limit_, params_nonconst.max_iterations_);
206 if (!optimization_result && replan_count < params_nonconst.max_recovery_attempts_)
221 params_nonconst.setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
223 ROS_DEBUG_NAMED(
"chomp_planner",
"Optimization actually took %f sec to run",
228 ROS_DEBUG_NAMED(
"chomp_planner",
"Output trajectory has %zd joints", trajectory.getNumJoints());
230 auto result = std::make_shared<robot_trajectory::RobotTrajectory>(
planning_scene->getRobotModel(), req.group_name);
232 for (
size_t i = 0; i < trajectory.getNumPoints(); i++)
234 const Eigen::MatrixXd::RowXpr source = trajectory.getTrajectoryPoint(i);
235 auto state = std::make_shared<moveit::core::RobotState>(start_state);
236 size_t joint_index = 0;
239 assert(jm->getVariableCount() == 1);
240 state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
242 result->addSuffixWayPoint(state, 0.0);
251 ROS_DEBUG_NAMED(
"chomp_planner",
"Serviced planning request in %f wall-seconds",
254 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
259 if (!optimizer->isCollisionFree())
262 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
269 for (
const moveit_msgs::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
271 if (!jc.configure(constraint) || !jc.decide(last_state).satisfied)
274 res.
error_code_.val = moveit_msgs::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;