Skip to content

Commit 60229db

Browse files
authored
Add KinematicsQueryOptions property in CartesianPath solver (#370)
1 parent d2918f1 commit 60229db

File tree

1 file changed

+6
-2
lines changed

1 file changed

+6
-2
lines changed

core/src/solvers/cartesian_path.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141

4242
#include <moveit/planning_scene/planning_scene.h>
4343
#include <moveit/trajectory_processing/time_parameterization.h>
44+
#include <moveit/kinematics_base/kinematics_base.h>
4445
#if MOVEIT_HAS_CARTESIAN_INTERPOLATOR
4546
#include <moveit/robot_state/cartesian_interpolator.h>
4647
#endif
@@ -56,6 +57,8 @@ CartesianPath::CartesianPath() {
5657
p.declare<double>("step_size", 0.01, "step size between consecutive waypoints");
5758
p.declare<double>("jump_threshold", 1.5, "acceptable fraction of mean joint motion per step");
5859
p.declare<double>("min_fraction", 1.0, "fraction of motion required for success");
60+
p.declare<kinematics::KinematicsQueryOptions>("kinematics_options", kinematics::KinematicsQueryOptions(),
61+
"KinematicsQueryOptions to pass to CartesianInterpolator");
5962
}
6063

6164
void CartesianPath::init(const core::RobotModelConstPtr& /*robot_model*/) {}
@@ -97,11 +100,12 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
97100
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
98101
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
99102
moveit::core::MaxEEFStep(props.get<double>("step_size")),
100-
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid);
103+
moveit::core::JumpThreshold(props.get<double>("jump_threshold")), is_valid,
104+
props.get<kinematics::KinematicsQueryOptions>("kinematics_options"));
101105
#else
102106
double achieved_fraction = sandbox_scene->getCurrentStateNonConst().computeCartesianPath(
103107
jmg, trajectory, &link, target, true, props.get<double>("step_size"), props.get<double>("jump_threshold"),
104-
is_valid);
108+
is_valid, props.get<kinematics::KinematicsQueryOptions>("kinematics_options"));
105109
#endif
106110

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

0 commit comments

Comments
 (0)