Skip to content

Commit

Permalink
feat: change params to speed up planning
Browse files Browse the repository at this point in the history
  • Loading branch information
Bariona committed Nov 21, 2024
1 parent 6487249 commit 26c63ea
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -255,10 +255,10 @@ PlanningContextManager::PlanningContextManager(moveit::core::RobotModelConstPtr
constraint_samplers::ConstraintSamplerManagerPtr csm)
: robot_model_(std::move(robot_model))
, constraint_sampler_manager_(std::move(csm))
, max_goal_samples_(10)
, max_state_sampling_attempts_(4)
, max_goal_samples_(400)
, max_state_sampling_attempts_(1)
, max_goal_sampling_attempts_(1000)
, max_planning_threads_(4)
, max_planning_threads_(8)
, max_solution_segment_length_(0.0)
, minimum_waypoint_count_(2)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ class TrajectoryGenerator
* @param sampling_time: sampling time of the generate trajectory
*/
void generate(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
planning_interface::MotionPlanResponse& res, double sampling_time = 0.1);
planning_interface::MotionPlanResponse& res, double sampling_time = 0.5);

protected:
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ void initMultiPlanRequestParameters(py::module& m)
moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters params{ node, planning_pipeline_names };
return params;
}))
.def_readonly("multi_plan_request_parameters",
.def_readwrite("multi_plan_request_parameters",
&moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters::plan_request_parameter_vector);
}
void initPlanningComponent(py::module& m)
Expand Down

1 comment on commit 26c63ea

@Bariona
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reasons for those changes:

  1. max_goal_samples_: increase it to let it support more goals to sample.

  2. max_state_sampling_attempts_: change it to 1 because IKFast is deterministic.

  3. max_planning_threads_: also increase it for more planning attempts.

  4. multi_plan_request_parameters: change the property to def_readwrite so that we can change the planner properties (e.g. planning speed/acceleration/time) during run time.

  5. double sampling_time: this is tricky. I tuned it high so that pilz LIN planner can have more chances of success (otherwise, you might easily get error saying that the trajectory's velocity goes beyond the limit).

Generally, the issue is due to how LIN generate a straight line trajectory: it will calculates ik for each waypoints and check whether each little "segments" satisfies the acceleration/velocity limits. For velocity check, the formula is generally: $\vec{v} = \Delta_{\text{joint pos}}/\Delta t$. So if you increase sampling_time (i.e. $\Delta t$), the velocity will be smaller.

Please sign in to comment.