Skip to content

Commit 99ccc11

Browse files
authored
Update API: JumpThreshold -> CartesianPrecision (moveit#611)
Python: Access properties via writable references This allows to modify properties in place, e.g. cartesian_solver.precision.translational = 0.01
1 parent 5a44808 commit 99ccc11

File tree

5 files changed

+35
-16
lines changed

5 files changed

+35
-16
lines changed

core/include/moveit/python/task_constructor/properties.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -64,9 +64,9 @@ class class_ : public pybind11::classh<type_, options...> // NOLINT(readability
6464
template <typename PropertyType, typename... Extra>
6565
class_& property(const char* name, const Extra&... extra) {
6666
PropertyConverter<PropertyType>(); // register corresponding property converter
67-
auto getter = [name](const type_& self) {
68-
const moveit::task_constructor::PropertyMap& props = self.properties();
69-
return props.get<PropertyType>(name);
67+
auto getter = [name](type_& self) -> PropertyType& {
68+
moveit::task_constructor::PropertyMap& props = self.properties();
69+
return const_cast<PropertyType&>(props.get<PropertyType>(name));
7070
};
7171
auto setter = [name](type_& self, const PropertyType& value) {
7272
moveit::task_constructor::PropertyMap& props = self.properties();

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

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

4141
#include <moveit/task_constructor/solvers/planner_interface.h>
42+
#include <moveit/robot_state/cartesian_interpolator.h>
4243

4344
namespace moveit {
4445
namespace task_constructor {
@@ -57,13 +58,17 @@ class CartesianPath : public PlannerInterface
5758
void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
5859

5960
void setStepSize(double step_size) { setProperty("step_size", step_size); }
60-
void setJumpThreshold(double jump_threshold) { setProperty("jump_threshold", jump_threshold); }
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+
}
6166
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }
6267

6368
[[deprecated("Replace with setMaxVelocityScalingFactor")]] // clang-format off
64-
void setMaxVelocityScaling(double factor) { setMaxVelocityScalingFactor(factor); }
69+
void setMaxVelocityScaling(double factor) { setMaxVelocityScalingFactor(factor); } // clang-format on
6570
[[deprecated("Replace with setMaxAccelerationScalingFactor")]] // clang-format off
66-
void setMaxAccelerationScaling(double factor) { setMaxAccelerationScalingFactor(factor); }
71+
void setMaxAccelerationScaling(double factor) { setMaxAccelerationScalingFactor(factor); } // clang-format on
6772

6873
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
6974

@@ -72,8 +77,8 @@ class CartesianPath : public PlannerInterface
7277
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
7378

7479
Result plan(const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
75-
const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target, const moveit::core::JointModelGroup* jmg,
76-
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,
7782
const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
7883
};
7984
} // namespace solvers

core/python/bindings/src/solvers.cpp

Lines changed: 19 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
#include <moveit/task_constructor/solvers/joint_interpolation.h>
3939
#include <moveit/task_constructor/solvers/multi_planner.h>
4040
#include <moveit_msgs/WorkspaceParameters.h>
41+
#include <fmt/core.h>
4142
#include "utils.h"
4243

4344
namespace py = pybind11;
@@ -99,6 +100,22 @@ void export_solvers(py::module& m) {
99100
.property<double>("max_step", "float: Limit any (single) joint change between two waypoints to this amount")
100101
.def(py::init<>());
101102

103+
const moveit::core::CartesianPrecision default_precision;
104+
py::class_<moveit::core::CartesianPrecision>(m, "CartesianPrecision", "precision for Cartesian interpolation")
105+
.def(py::init([](double translational, double rotational, double max_resolution) {
106+
return new moveit::core::CartesianPrecision{ translational, rotational, max_resolution };
107+
}),
108+
py::arg("translational") = default_precision.translational,
109+
py::arg("rotational") = default_precision.rotational,
110+
py::arg("max_resolution") = default_precision.max_resolution)
111+
.def_readwrite("translational", &moveit::core::CartesianPrecision::translational)
112+
.def_readwrite("rotational", &moveit::core::CartesianPrecision::rotational)
113+
.def_readwrite("max_resolution", &moveit::core::CartesianPrecision::max_resolution)
114+
.def("__str__", [](const moveit::core::CartesianPrecision& self) {
115+
return fmt::format("CartesianPrecision(translational={}, rotational={}, max_resolution={}",
116+
self.translational, self.rotational, self.max_resolution);
117+
});
118+
102119
properties::class_<CartesianPath, PlannerInterface>(m, "CartesianPath", R"(
103120
Perform linear interpolation between Cartesian poses.
104121
Fails on collision along the interpolation path. There is no obstacle avoidance. ::
@@ -108,15 +125,12 @@ void export_solvers(py::module& m) {
108125
# Instantiate Cartesian-space interpolation planner
109126
cartesianPlanner = core.CartesianPath()
110127
cartesianPlanner.step_size = 0.01
111-
cartesianPlanner.jump_threshold = 0.0 # effectively disable jump threshold.
128+
cartesianPlanner.precision.translational = 0.001
112129
)")
113130
.property<double>("step_size", "float: Limit the Cartesian displacement between consecutive waypoints "
114131
"In contrast to joint-space interpolation, the Cartesian planner can also "
115132
"succeed when only a fraction of the linear path was feasible.")
116-
.property<double>(
117-
"jump_threshold",
118-
"float: Limit joint displacement between consecutive waypoints, thus preventing jumps in joint space. "
119-
"This values specifies the fraction of mean acceptable joint motion per step.")
133+
.property<moveit::core::CartesianPrecision>("precision", "Cartesian interpolation precision")
120134
.property<double>("min_fraction", "float: Fraction of overall distance required to succeed.")
121135
.def(py::init<>());
122136

core/src/solvers/cartesian_path.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,8 @@ CartesianPath::CartesianPath() {
5454
auto& p = properties();
5555
p.declare<geometry_msgs::PoseStamped>("ik_frame", "frame to move linearly (use for joint-space target)");
5656
p.declare<double>("step_size", 0.01, "step size between consecutive waypoints");
57-
p.declare<double>("jump_threshold", 1.5, "acceptable fraction of mean joint motion per step");
57+
p.declare<moveit::core::CartesianPrecision>("precision", moveit::core::CartesianPrecision(),
58+
"precision of linear path");
5859
p.declare<double>("min_fraction", 1.0, "fraction of motion required for success");
5960
p.declare<kinematics::KinematicsQueryOptions>("kinematics_options", kinematics::KinematicsQueryOptions(),
6061
"KinematicsQueryOptions to pass to CartesianInterpolator");
@@ -112,7 +113,7 @@ PlannerInterface::Result CartesianPath::plan(const planning_scene::PlanningScene
112113
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
113114
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
114115
moveit::core::MaxEEFStep(props.get<double>("step_size")),
115-
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid,
116+
props.get<moveit::core::CartesianPrecision>("precision"), is_valid,
116117
props.get<kinematics::KinematicsQueryOptions>("kinematics_options"), offset);
117118

118119
assert(!trajectory.empty()); // there should be at least the start state

demo/src/fallbacks_move_to.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,6 @@ int main(int argc, char** argv) {
3535

3636
// setup solvers
3737
auto cartesian = std::make_shared<solvers::CartesianPath>();
38-
cartesian->setJumpThreshold(2.0);
3938

4039
auto ptp = std::make_shared<solvers::PipelinePlanner>("pilz_industrial_motion_planner");
4140
ptp->setPlannerId("PTP");

0 commit comments

Comments
 (0)