Skip to content

Commit

Permalink
reducing the minimum velicity scaling factor to enable slower motions
Browse files Browse the repository at this point in the history
  • Loading branch information
vivekcdavid authored Nov 29, 2024
1 parent a35a3c9 commit e142a50
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Clock> clock_;
Expand Down

0 comments on commit e142a50

Please sign in to comment.