@@ -59,14 +59,16 @@ class CartesianPath : public PlannerInterface
59
59
60
60
void setStepSize (double step_size) { setProperty (" step_size" , step_size); }
61
61
void setPrecision (const moveit::core::CartesianPrecision& precision) { setProperty (" precision" , precision); }
62
- [[deprecated(" Replace with setPrecision" )]] // clang-format off
63
- void setJumpThreshold (double /* jump_threshold*/ ) {}
62
+ template <typename T = float >
63
+ void setJumpThreshold (double ) {
64
+ static_assert (std::is_integral<T>::value, " setJumpThreshold() is deprecated. Replace with setPrecision." );
65
+ }
64
66
void setMinFraction (double min_fraction) { setProperty (" min_fraction" , min_fraction); }
65
67
66
68
[[deprecated(" Replace with setMaxVelocityScalingFactor" )]] // clang-format off
67
- void setMaxVelocityScaling (double factor) { setMaxVelocityScalingFactor (factor); }
69
+ void setMaxVelocityScaling (double factor) { setMaxVelocityScalingFactor (factor); } // clang-format on
68
70
[[deprecated(" Replace with setMaxAccelerationScalingFactor" )]] // clang-format off
69
- void setMaxAccelerationScaling (double factor) { setMaxAccelerationScalingFactor (factor); }
71
+ void setMaxAccelerationScaling (double factor) { setMaxAccelerationScalingFactor (factor); } // clang-format on
70
72
71
73
void init (const moveit::core::RobotModelConstPtr& robot_model) override ;
72
74
@@ -75,8 +77,8 @@ class CartesianPath : public PlannerInterface
75
77
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override ;
76
78
77
79
Result plan (const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
78
- const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg,
79
- double timeout, robot_trajectory::RobotTrajectoryPtr& result,
80
+ const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target,
81
+ const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
80
82
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override ;
81
83
};
82
84
} // namespace solvers
0 commit comments