Skip to content

Commit 02541e5

Browse files
committed
Revert "Update API: JumpThreshold -> CartesianPrecision (#611)"
This reverts commit 99ccc11.
1 parent c567c7b commit 02541e5

File tree

4 files changed

+9
-27
lines changed

4 files changed

+9
-27
lines changed

core/include/moveit/task_constructor/solvers/cartesian_path.h

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,6 @@
3939
#pragma once
4040

4141
#include <moveit/task_constructor/solvers/planner_interface.h>
42-
#include <moveit/robot_state/cartesian_interpolator.h>
4342

4443
namespace moveit {
4544
namespace task_constructor {
@@ -58,11 +57,7 @@ class CartesianPath : public PlannerInterface
5857
void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
5958

6059
void setStepSize(double step_size) { setProperty("step_size", step_size); }
61-
void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); }
62-
template <typename T = float>
63-
void setJumpThreshold(double) {
64-
static_assert(std::is_integral<T>::value, "setJumpThreshold() is deprecated. Replace with setPrecision.");
65-
}
60+
void setJumpThreshold(double jump_threshold) { setProperty("jump_threshold", jump_threshold); }
6661
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }
6762

6863
[[deprecated("Replace with setMaxVelocityScalingFactor")]] // clang-format off

core/python/bindings/src/solvers.cpp

Lines changed: 5 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -97,22 +97,6 @@ void export_solvers(py::module& m) {
9797
.property<double>("max_step", "float: Limit any (single) joint change between two waypoints to this amount")
9898
.def(py::init<>());
9999

100-
const moveit::core::CartesianPrecision default_precision;
101-
py::class_<moveit::core::CartesianPrecision>(m, "CartesianPrecision", "precision for Cartesian interpolation")
102-
.def(py::init([](double translational, double rotational, double max_resolution) {
103-
return new moveit::core::CartesianPrecision{ translational, rotational, max_resolution };
104-
}),
105-
py::arg("translational") = default_precision.translational,
106-
py::arg("rotational") = default_precision.rotational,
107-
py::arg("max_resolution") = default_precision.max_resolution)
108-
.def_readwrite("translational", &moveit::core::CartesianPrecision::translational)
109-
.def_readwrite("rotational", &moveit::core::CartesianPrecision::rotational)
110-
.def_readwrite("max_resolution", &moveit::core::CartesianPrecision::max_resolution)
111-
.def("__str__", [](const moveit::core::CartesianPrecision& self) {
112-
return fmt::format("CartesianPrecision(translational={}, rotational={}, max_resolution={}",
113-
self.translational, self.rotational, self.max_resolution);
114-
});
115-
116100
properties::class_<CartesianPath, PlannerInterface>(m, "CartesianPath", R"(
117101
Perform linear interpolation between Cartesian poses.
118102
Fails on collision along the interpolation path. There is no obstacle avoidance. ::
@@ -122,12 +106,15 @@ void export_solvers(py::module& m) {
122106
# Instantiate Cartesian-space interpolation planner
123107
cartesianPlanner = core.CartesianPath()
124108
cartesianPlanner.step_size = 0.01
125-
cartesianPlanner.precision.translational = 0.001
109+
cartesianPlanner.jump_threshold = 0.0 # effectively disable jump threshold.
126110
)")
127111
.property<double>("step_size", "float: Limit the Cartesian displacement between consecutive waypoints "
128112
"In contrast to joint-space interpolation, the Cartesian planner can also "
129113
"succeed when only a fraction of the linear path was feasible.")
130-
.property<moveit::core::CartesianPrecision>("precision", "Cartesian interpolation precision")
114+
.property<double>(
115+
"jump_threshold",
116+
"float: Limit joint displacement between consecutive waypoints, thus preventing jumps in joint space. "
117+
"This values specifies the fraction of mean acceptable joint motion per step.")
131118
.property<double>("min_fraction", "float: Fraction of overall distance required to succeed.")
132119
.def(py::init<>());
133120

core/src/solvers/cartesian_path.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,7 @@ CartesianPath::CartesianPath() {
6060
auto& p = properties();
6161
p.declare<geometry_msgs::msg::PoseStamped>("ik_frame", "frame to move linearly (use for joint-space target)");
6262
p.declare<double>("step_size", 0.01, "step size between consecutive waypoints");
63-
p.declare<moveit::core::CartesianPrecision>("precision", moveit::core::CartesianPrecision(),
64-
"precision of linear path");
63+
p.declare<double>("jump_threshold", 1.5, "acceptable fraction of mean joint motion per step");
6564
p.declare<double>("min_fraction", 1.0, "fraction of motion required for success");
6665
p.declare<kinematics::KinematicsQueryOptions>("kinematics_options", kinematics::KinematicsQueryOptions(),
6766
"KinematicsQueryOptions to pass to CartesianInterpolator");
@@ -121,7 +120,7 @@ PlannerInterface::Result CartesianPath::plan(const planning_scene::PlanningScene
121120
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
122121
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
123122
moveit::core::MaxEEFStep(props.get<double>("step_size")),
124-
props.get<moveit::core::CartesianPrecision>("precision"), is_valid,
123+
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid,
125124
props.get<kinematics::KinematicsQueryOptions>("kinematics_options"),
126125
props.get<kinematics::KinematicsBase::IKCostFn>("kinematics_cost_fn"), offset);
127126

demo/src/fallbacks_move_to.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ int main(int argc, char** argv) {
3434

3535
// setup solvers
3636
auto cartesian = std::make_shared<solvers::CartesianPath>();
37+
cartesian->setJumpThreshold(2.0);
3738

3839
const auto ptp = [&node]() {
3940
auto pp{ std::make_shared<solvers::PipelinePlanner>(node, "pilz_industrial_motion_planner", "PTP") };

0 commit comments

Comments
 (0)