Skip to content

Commit cc7f9f0

Browse files
committed
Merge branch 'master' into ros2
2 parents cb867ae + 99ccc11 commit cc7f9f0

File tree

23 files changed

+180
-37
lines changed

23 files changed

+180
-37
lines changed

.github/workflows/ci.yaml

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -59,15 +59,14 @@ jobs:
5959
submodules: recursive
6060

6161
- name: Cache ccache
62-
uses: rhaschke/cache@main
62+
uses: actions/cache@v4
6363
with:
64+
save-always: true
6465
path: ${{ env.CCACHE_DIR }}
6566
key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }}
6667
restore-keys: |
6768
ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}
6869
ccache-${{ env.CACHE_PREFIX }}
69-
env:
70-
GHA_CACHE_SAVE: always
7170
7271
- id: ici
7372
name: Run industrial_ci

.gitmodules

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,3 +3,6 @@
33
url = https://github.com/pybind/pybind11
44
branch = smart_holder
55
shallow = true
6+
[submodule "core/src/scope_guard"]
7+
path = core/src/scope_guard
8+
url = https://github.com/ricab/scope_guard

.pre-commit-config.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ repos:
2929
- id: trailing-whitespace
3030

3131
- repo: https://github.com/psf/black
32-
rev: 22.3.0
32+
rev: 24.8.0
3333
hooks:
3434
- id: black
3535
args: ["--line-length", "100"]

capabilities/src/execute_task_solution_capability.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -185,8 +185,10 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
185185
exec_traj.effect_on_success = [this,
186186
&scene_diff = const_cast<::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff),
187187
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
188+
// Never modify joint state directly (only via robot trajectories)
188189
scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
189190
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
191+
scene_diff.robot_state.is_diff = true; // silent empty JointState msg error
190192

191193
if (!moveit::core::isEmpty(scene_diff)) {
192194
RCLCPP_DEBUG_STREAM(LOGGER, "apply effect of " << description);

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::msg::Constraints& path_constraints = moveit_msgs::msg::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::msg::Constraints& path_constraints = moveit_msgs::msg::Constraints()) override;
7883

7984
std::string getPlannerId() const override { return "CartesianPath"; }

core/include/moveit/task_constructor/stage_p.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,13 @@
5757
namespace moveit {
5858
namespace task_constructor {
5959

60+
/// exception thrown by StagePrivate::runCompute()
61+
class PreemptStageException : public std::exception
62+
{
63+
public:
64+
explicit PreemptStageException() {}
65+
};
66+
6067
class ContainerBase;
6168
class StagePrivate
6269
{
@@ -146,6 +153,10 @@ class StagePrivate
146153
bool storeFailures() const { return introspection_ != nullptr; }
147154
void runCompute() {
148155
RCLCPP_DEBUG_STREAM(LOGGER, fmt::format("Computing stage '{}'", name()));
156+
157+
if (preempted())
158+
throw PreemptStageException();
159+
149160
auto compute_start_time = std::chrono::steady_clock::now();
150161
try {
151162
compute();
@@ -159,6 +170,11 @@ class StagePrivate
159170
/** compute cost for solution through configured CostTerm */
160171
void computeCost(const InterfaceState& from, const InterfaceState& to, SolutionBase& solution);
161172

173+
void setPreemptRequestedMember(const std::atomic<bool>* preempt_requested) {
174+
preempt_requested_ = preempt_requested;
175+
}
176+
bool preempted() const { return preempt_requested_ != nullptr && *preempt_requested_; }
177+
162178
protected:
163179
StagePrivate& operator=(StagePrivate&& other);
164180

@@ -197,6 +213,8 @@ class StagePrivate
197213
InterfaceWeakPtr next_starts_; // interface to be used for sendForward()
198214

199215
Introspection* introspection_; // task's introspection instance
216+
const std::atomic<bool>* preempt_requested_;
217+
200218
inline static const rclcpp::Logger LOGGER = rclcpp::get_logger("stage");
201219
};
202220
PIMPL_FUNCTIONS(Stage)

core/include/moveit/task_constructor/task.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -129,8 +129,9 @@ class Task : protected WrapperBase
129129

130130
/// reset, init scene (if not yet done), and init all stages, then start planning
131131
moveit::core::MoveItErrorCode plan(size_t max_solutions = 0);
132-
/// interrupt current planning (or execution)
132+
/// interrupt current planning
133133
void preempt();
134+
void resetPreemptRequest();
134135
/// execute solution, return the result
135136
moveit::core::MoveItErrorCode execute(const SolutionBase& s);
136137

core/include/moveit/task_constructor/task_p.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class TaskPrivate : public WrapperBasePrivate
6363
std::string ns_;
6464
robot_model_loader::RobotModelLoaderPtr robot_model_loader_;
6565
moveit::core::RobotModelConstPtr robot_model_;
66-
bool preempt_requested_;
66+
std::atomic<bool> preempt_requested_;
6767

6868
// introspection and monitoring
6969
std::unique_ptr<Introspection> introspection_;

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/msg/workspace_parameters.hpp>
41+
#include <fmt/core.h>
4142
#include "utils.h"
4243

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

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+
99116
properties::class_<CartesianPath, PlannerInterface>(m, "CartesianPath", R"(
100117
Perform linear interpolation between Cartesian poses.
101118
Fails on collision along the interpolation path. There is no obstacle avoidance. ::
@@ -105,15 +122,12 @@ void export_solvers(py::module& m) {
105122
# Instantiate Cartesian-space interpolation planner
106123
cartesianPlanner = core.CartesianPath()
107124
cartesianPlanner.step_size = 0.01
108-
cartesianPlanner.jump_threshold = 0.0 # effectively disable jump threshold.
125+
cartesianPlanner.precision.translational = 0.001
109126
)")
110127
.property<double>("step_size", "float: Limit the Cartesian displacement between consecutive waypoints "
111128
"In contrast to joint-space interpolation, the Cartesian planner can also "
112129
"succeed when only a fraction of the linear path was feasible.")
113-
.property<double>(
114-
"jump_threshold",
115-
"float: Limit joint displacement between consecutive waypoints, thus preventing jumps in joint space. "
116-
"This values specifies the fraction of mean acceptable joint motion per step.")
130+
.property<moveit::core::CartesianPrecision>("precision", "Cartesian interpolation precision")
117131
.property<double>("min_fraction", "float: Fraction of overall distance required to succeed.")
118132
.def(py::init<>());
119133

core/python/test/test_mtc.py

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,10 +14,14 @@ def setUpModule():
1414
rclcpp.init()
1515

1616

17+
def tearDownModule():
18+
rclcpp.shutdown()
19+
20+
1721
# When py_binding_tools and MTC are compiled with different pybind11 versions,
1822
# the corresponding classes are not interoperable.
1923
def check_pybind11_incompatibility():
20-
rclcpp.init([])
24+
rclcpp.init()
2125
node = rclcpp.Node("dummy")
2226
try:
2327
core.PipelinePlanner(node)
@@ -33,8 +37,8 @@ def check_pybind11_incompatibility():
3337

3438

3539
class TestPropertyMap(unittest.TestCase):
40+
3641
def setUp(self):
37-
self.node = rclcpp.Node("test_mtc_props")
3842
self.props = core.PropertyMap()
3943

4044
def _check(self, name, value):
@@ -54,7 +58,8 @@ def test_assign(self):
5458

5559
@unittest.skipIf(incompatible_pybind11, incompatible_pybind11_msg)
5660
def test_assign_in_reference(self):
57-
planner = core.PipelinePlanner(self.node)
61+
node = rclcpp.Node("test_mtc_props")
62+
planner = core.PipelinePlanner(node)
5863
props = planner.properties
5964

6065
props["goal_joint_tolerance"] = 3.14

core/src/scope_guard

Submodule scope_guard added at 71a0452

core/src/solvers/cartesian_path.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,8 @@ 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<double>("jump_threshold", 1.5, "acceptable fraction of mean joint motion per step");
63+
p.declare<moveit::core::CartesianPrecision>("precision", moveit::core::CartesianPrecision(),
64+
"precision of linear path");
6465
p.declare<double>("min_fraction", 1.0, "fraction of motion required for success");
6566
p.declare<kinematics::KinematicsQueryOptions>("kinematics_options", kinematics::KinematicsQueryOptions(),
6667
"KinematicsQueryOptions to pass to CartesianInterpolator");
@@ -120,7 +121,7 @@ PlannerInterface::Result CartesianPath::plan(const planning_scene::PlanningScene
120121
double achieved_fraction = moveit::core::CartesianInterpolator::computeCartesianPath(
121122
&(sandbox_scene->getCurrentStateNonConst()), jmg, trajectory, &link, target, true,
122123
moveit::core::MaxEEFStep(props.get<double>("step_size")),
123-
moveit::core::JumpThreshold::relative(props.get<double>("jump_threshold")), is_valid,
124+
props.get<moveit::core::CartesianPrecision>("precision"), is_valid,
124125
props.get<kinematics::KinematicsQueryOptions>("kinematics_options"),
125126
props.get<kinematics::KinematicsBase::IKCostFn>("kinematics_cost_fn"), offset);
126127

core/src/stage.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,8 @@ StagePrivate::StagePrivate(Stage* me, const std::string& name)
102102
, cost_term_{ std::make_unique<CostTerm>() }
103103
, total_compute_time_{}
104104
, parent_{ nullptr }
105-
, introspection_{ nullptr } {}
105+
, introspection_{ nullptr }
106+
, preempt_requested_{ nullptr } {}
106107

107108
StagePrivate& StagePrivate::operator=(StagePrivate&& other) {
108109
assert(typeid(*this) == typeid(other));

core/src/stages/move_relative.cpp

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -191,6 +191,11 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning
191191

192192
double max_distance = props.get<double>("max_distance");
193193
double min_distance = props.get<double>("min_distance");
194+
195+
// if min_distance == max_distance, resort to moving full distance (negative min_distance)
196+
if (max_distance > 0.0 && std::fabs(max_distance - min_distance) < std::numeric_limits<double>::epsilon())
197+
min_distance = -1.0;
198+
194199
const auto& path_constraints = props.get<moveit_msgs::msg::Constraints>("path_constraints");
195200

196201
robot_trajectory::RobotTrajectoryPtr robot_trajectory;
@@ -300,7 +305,8 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning
300305
comment = result.message;
301306
solution.setPlannerId(planner_->getPlannerId());
302307

303-
if (robot_trajectory) { // the following requires a robot_trajectory returned from planning
308+
if (robot_trajectory && robot_trajectory->getWayPointCount() > 0) { // the following requires a robot_trajectory
309+
// returned from planning
304310
moveit::core::RobotStatePtr& reached_state = robot_trajectory->getLastWayPointPtr();
305311
reached_state->updateLinkTransforms();
306312
const Eigen::Isometry3d& reached_pose = reached_state->getGlobalLinkTransform(link) * offset;
@@ -335,7 +341,7 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning
335341
}
336342

337343
// store result
338-
if (robot_trajectory) {
344+
if (robot_trajectory && robot_trajectory->getWayPointCount() > 0) {
339345
scene->setCurrentState(robot_trajectory->getLastWayPoint());
340346
if (dir == Interface::BACKWARD)
341347
robot_trajectory->reverse();

core/src/task.cpp

Lines changed: 17 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@
4646
#include <moveit/robot_model_loader/robot_model_loader.h>
4747
#include <moveit/planning_pipeline/planning_pipeline.h>
4848

49+
#include <scope_guard/scope_guard.hpp>
50+
4951
#include <functional>
5052

5153
using namespace std::chrono_literals;
@@ -214,11 +216,12 @@ void Task::init() {
214216
// task expects its wrapped child to push to both ends, this triggers interface resolution
215217
stages()->pimpl()->resolveInterface(InterfaceFlags({ GENERATE }));
216218

217-
// provide introspection instance to all stages
219+
// provide introspection instance and preempt_requested to all stages
218220
auto* introspection = impl->introspection_.get();
219221
impl->traverseStages(
220-
[introspection](Stage& stage, int /*depth*/) {
222+
[introspection, impl](Stage& stage, int /*depth*/) {
221223
stage.pimpl()->setIntrospection(introspection);
224+
stage.pimpl()->setPreemptRequestedMember(&impl->preempt_requested_);
222225
return true;
223226
},
224227
1, UINT_MAX);
@@ -233,10 +236,17 @@ bool Task::canCompute() const {
233236
}
234237

235238
void Task::compute() {
236-
stages()->pimpl()->runCompute();
239+
try {
240+
stages()->pimpl()->runCompute();
241+
} catch (const PreemptStageException& e) {
242+
// do nothing, needed for early stop
243+
}
237244
}
238245

239246
moveit::core::MoveItErrorCode Task::plan(size_t max_solutions) {
247+
// ensure the preempt request is resetted once this method exits
248+
auto guard = sg::make_scope_guard([this]() noexcept { this->resetPreemptRequest(); });
249+
240250
auto impl = pimpl();
241251
init();
242252

@@ -248,7 +258,6 @@ moveit::core::MoveItErrorCode Task::plan(size_t max_solutions) {
248258
explainFailure();
249259
return error_code;
250260
};
251-
impl->preempt_requested_ = false;
252261
const double available_time = timeout();
253262
const auto start_time = std::chrono::steady_clock::now();
254263
while (canCompute() && (max_solutions == 0 || numSolutions() < max_solutions)) {
@@ -269,6 +278,10 @@ void Task::preempt() {
269278
pimpl()->preempt_requested_ = true;
270279
}
271280

281+
void Task::resetPreemptRequest() {
282+
pimpl()->preempt_requested_ = false;
283+
}
284+
272285
moveit::core::MoveItErrorCode Task::execute(const SolutionBase& s) {
273286
// Add random ID to prevent warnings about multiple publishers within the same node
274287
auto node = rclcpp::Node::make_shared("moveit_task_constructor_executor_" +

0 commit comments

Comments
 (0)