From e142a502a27aabb53be12769f03e0a40bad2c25e Mon Sep 17 00:00:00 2001 From: vivekcdavid <111999394+vivekcdavid@users.noreply.github.com> Date: Fri, 29 Nov 2024 14:09:24 +0100 Subject: [PATCH] reducing the minimum velicity scaling factor to enable slower motions --- .../pilz_industrial_motion_planner/trajectory_generator.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index cdbf91babf..6df353aeb1 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -279,7 +279,7 @@ class TrajectoryGenerator protected: const moveit::core::RobotModelConstPtr robot_model_; const pilz_industrial_motion_planner::LimitsContainer planner_limits_; - static constexpr double MIN_SCALING_FACTOR{ 0.0001 }; + static constexpr double MIN_SCALING_FACTOR{ 0.0000001 }; static constexpr double MAX_SCALING_FACTOR{ 1. }; static constexpr double VELOCITY_TOLERANCE{ 1e-8 }; const std::unique_ptr clock_;