41 #include <tf2/LinearMath/Quaternion.h>
42 #include <tf2_eigen/tf2_eigen.hpp>
43 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
49 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"chomp_planner");
55 auto start_time = std::chrono::system_clock::now();
58 RCLCPP_ERROR(LOGGER,
"No planning scene initialized.");
59 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
69 RCLCPP_ERROR(LOGGER,
"Start state violates joint limits");
70 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
77 if (req.goal_constraints.size() != 1)
79 RCLCPP_ERROR(LOGGER,
"Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
80 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
84 if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
85 !req.goal_constraints[0].orientation_constraints.empty())
87 RCLCPP_ERROR(LOGGER,
"Only joint-space goals are supported");
88 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
94 for (
const moveit_msgs::msg::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
98 RCLCPP_ERROR(LOGGER,
"Goal state violates joint limits");
99 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
102 robotStateToArray(goal_state, req.group_name, trajectory.
getTrajectoryPoint(goal_index));
105 planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
113 if (revolute_joint !=
nullptr)
117 double start = (trajectory)(0, i);
118 double end = (trajectory)(goal_index, i);
119 RCLCPP_INFO(LOGGER,
"Start is %f end %f short %f", start, end, shortestAngularDistance(start, end));
120 (trajectory)(goal_index, i) = start + shortestAngularDistance(start, end);
136 RCLCPP_ERROR(LOGGER,
"Input trajectory has less than 2 points, "
137 "trajectory must contain at least start and goal state");
143 RCLCPP_ERROR(LOGGER,
"invalid interpolation method specified in the chomp_planner file");
147 RCLCPP_INFO(LOGGER,
"CHOMP trajectory initialized using method: %s ",
151 auto create_time = std::chrono::system_clock::now();
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;
164 std::unique_ptr<ChompOptimizer> optimizer;
183 std::make_unique<ChompOptimizer>(&trajectory,
planning_scene, req.group_name, ¶ms_nonconst, start_state);
184 if (!optimizer->isInitialized())
186 RCLCPP_ERROR(LOGGER,
"Could not initialize optimizer");
187 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
191 RCLCPP_DEBUG(LOGGER,
"Optimization took %ld sec to create",
192 (std::chrono::system_clock::now() - create_time).count());
194 bool optimization_result = optimizer->optimize();
200 "Planned with Chomp Parameters (learning_rate, ridge_factor, "
201 "planning_time_limit, max_iterations), attempt: # %d ",
203 RCLCPP_INFO(LOGGER,
"Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
222 params_nonconst.
setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
224 RCLCPP_DEBUG(LOGGER,
"Optimization actually took %ld sec to run",
225 (std::chrono::system_clock::now() - create_time).count());
226 create_time = std::chrono::system_clock::now();
229 RCLCPP_DEBUG(LOGGER,
"Output trajectory has %zd joints", trajectory.
getNumJoints());
231 auto result = std::make_shared<robot_trajectory::RobotTrajectory>(
planning_scene->getRobotModel(), req.group_name);
236 auto state = std::make_shared<moveit::core::RobotState>(start_state);
237 size_t joint_index = 0;
240 assert(jm->getVariableCount() == 1);
241 state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
243 result->addSuffixWayPoint(state, 0.0);
249 RCLCPP_DEBUG(LOGGER,
"Bottom took %ld sec to create", (std::chrono::system_clock::now() - create_time).count());
250 RCLCPP_DEBUG(LOGGER,
"Serviced planning request in %ld wall-seconds",
251 (std::chrono::system_clock::now() - start_time).count());
253 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
255 res.
processing_time_[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
258 if (not optimizer->isCollisionFree())
260 RCLCPP_ERROR(LOGGER,
"Motion plan is invalid.");
261 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
268 for (
const moveit_msgs::msg::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
272 RCLCPP_ERROR(LOGGER,
"Goal constraints are violated: %s", constraint.joint_name.c_str());
273 res.
error_code_.val = moveit_msgs::msg::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;
279 res.
processing_time_[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
double planning_time_limit_
std::string trajectory_initialization_method_
void setRecoveryParams(double learning_rate, double ridge_factor, int planning_time_limit, int max_iterations)
int max_recovery_attempts_
bool enable_failure_recovery_
bool solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, const ChompParameters ¶ms, planning_interface::MotionPlanDetailedResponse &res) const
Represents a discretized joint-space trajectory for CHOMP.
size_t getNumPoints() const
Gets the number of points in the trajectory.
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
bool fillInFromTrajectory(const robot_trajectory::RobotTrajectory &trajectory)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e....
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Class for handling single DOF joint constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
bool isContinuous() const
Check if this joint wraps around.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
bool satisfiesBounds(double margin=0.0) const
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
bool satisfied
Whether or not the constraint or constraints were satisfied.
moveit_msgs::msg::MoveItErrorCodes error_code_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
std::vector< double > processing_time_