Skip to content

Commit f282f8b

Browse files
authored
Merge pull request #9 from sjahr/pr-merge_upstream_ros2
Merge upstream ros2
2 parents 6cb0c2b + cf5cf4a commit f282f8b

File tree

84 files changed

+951
-527
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

84 files changed

+951
-527
lines changed

.github/workflows/ci.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,6 @@ jobs:
1919
fail-fast: false
2020
matrix:
2121
env:
22-
- IMAGE: humble-source
2322
- IMAGE: rolling-source
2423
NAME: ccov
2524
TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"

.github/workflows/prerelease.yaml

+41
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git).
2+
# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst)
3+
4+
name: pre-release
5+
6+
on:
7+
workflow_dispatch:
8+
9+
permissions:
10+
contents: read # to fetch code (actions/checkout)
11+
12+
jobs:
13+
default:
14+
strategy:
15+
matrix:
16+
distro: [noetic]
17+
18+
env:
19+
# https://github.com/ros-industrial/industrial_ci/issues/666
20+
BUILDER: catkin_make_isolated
21+
ROS_DISTRO: ${{ matrix.distro }}
22+
PRERELEASE: true
23+
BASEDIR: ${{ github.workspace }}/.work
24+
25+
name: "${{ matrix.distro }}"
26+
runs-on: ubuntu-latest
27+
steps:
28+
- name: "Free up disk space"
29+
run: |
30+
sudo apt-get -qq purge build-essential "ghc*"
31+
sudo apt-get clean
32+
# cleanup docker images not used by us
33+
docker system prune -af
34+
# free up a lot of stuff from /usr/local
35+
sudo rm -rf /usr/local
36+
df -h
37+
- uses: actions/checkout@v3
38+
with:
39+
submodules: recursive
40+
- name: industrial_ci
41+
uses: ros-industrial/industrial_ci@master

.gitmodules

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
[submodule "core/python/pybind11"]
22
path = core/python/pybind11
3-
url = https://github.com/rhaschke/pybind11
3+
url = https://github.com/pybind/pybind11
44
branch = smart_holder
55
shallow = true

capabilities/CHANGELOG.rst

+9
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,15 @@
22
Changelog for package moveit_task_constructor_capabilities
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.1.3 (2023-03-06)
6+
------------------
7+
8+
0.1.2 (2023-02-24)
9+
------------------
10+
11+
0.1.1 (2023-02-15)
12+
------------------
13+
514
0.1.0 (2023-02-02)
615
------------------
716
* Initial release

capabilities/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<package format="2">
22
<name>moveit_task_constructor_capabilities</name>
3-
<version>0.1.0</version>
3+
<version>0.1.3</version>
44
<description>
55
MoveGroupCapabilites to interact with MoveIt
66
</description>

capabilities/src/execute_task_solution_capability.cpp

+17-16
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ void ExecuteTaskSolutionCapability::initialize() {
9494
std::placeholders::_1, std::placeholders::_2)),
9595
ActionServerType::CancelCallback(
9696
std::bind(&ExecuteTaskSolutionCapability::preemptCallback, this, std::placeholders::_1)),
97-
[this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>> goal_handle) {
97+
[this](const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle) {
9898
last_goal_future_ =
9999
std::async(std::launch::async, &ExecuteTaskSolutionCapability::goalCallback, this, goal_handle);
100100
});
@@ -176,19 +176,20 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
176176
};
177177

178178
auto make_apply_planning_scene_diff_cb = [this](const std::vector<moveit_msgs::msg::PlanningScene>& scene_diffs) {
179-
return
180-
[this, scene_diffs = std::move(scene_diffs)](const plan_execution::ExecutableMotionPlan* /*plan*/) mutable {
181-
for (auto& scene_diff : scene_diffs) {
182-
if (!moveit::core::isEmpty(scene_diff)) {
183-
/* RCLCPP_DEBUG_STREAM(LOGGER, "apply effect of " << description); */
184-
scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
185-
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
186-
if (!context_->planning_scene_monitor_->newPlanningSceneMessage(scene_diff))
187-
return false;
188-
}
189-
}
190-
return true;
191-
};
179+
return [this,
180+
&scene_diffs = std::as_const(scene_diffs)](const plan_execution::ExecutableMotionPlan* /*plan*/) mutable {
181+
for (auto& const_scene_diff : scene_diffs) {
182+
if (!moveit::core::isEmpty(const_scene_diff)) {
183+
/* RCLCPP_DEBUG_STREAM(LOGGER, "apply effect of " << description); */
184+
moveit_msgs::msg::PlanningScene scene_diff = const_scene_diff;
185+
scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
186+
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
187+
if (!context_->planning_scene_monitor_->newPlanningSceneMessage(scene_diff))
188+
return false;
189+
}
190+
}
191+
return true;
192+
};
192193
};
193194
auto make_description = [size = solution.sub_trajectory.size()](const std::size_t index) {
194195
return std::to_string(index + 1) + "/" + std::to_string(size);
@@ -218,5 +219,5 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
218219

219220
} // namespace move_group
220221

221-
#include <class_loader/class_loader.hpp>
222-
CLASS_LOADER_REGISTER_CLASS(move_group::ExecuteTaskSolutionCapability, move_group::MoveGroupCapability)
222+
#include <pluginlib/class_list_macros.hpp>
223+
PLUGINLIB_EXPORT_CLASS(move_group::ExecuteTaskSolutionCapability, move_group::MoveGroupCapability)

core/CHANGELOG.rst

+29
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,35 @@
22
Changelog for package moveit_task_constructor_core
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.1.3 (2023-03-06)
6+
------------------
7+
* MoveRelative: Allow backwards operation for joint-space delta (`#436 <https://github.com/ros-planning/moveit_task_constructor/issues/436>`_)
8+
* ComputeIK: Limit collision checking to JMG (`#428 <https://github.com/ros-planning/moveit_task_constructor/issues/428>`_)
9+
* Fix: Fetch pybind11 submodule if not yet present
10+
* Contributors: Robert Haschke
11+
12+
0.1.2 (2023-02-24)
13+
------------------
14+
* Remove moveit/__init__.py during .deb builds to avoid installation conflicts
15+
* MultiPlanner solver (`#429 <https://github.com/ros-planning/moveit_task_constructor/issues/429>`_): a planner that tries multiple planners in sequence
16+
17+
* CartesianPath: Deprecate redundant property setters
18+
* PlannerInterface: provide "timeout" property
19+
* PlannerInterface: provide setters for properties
20+
* JointInterpolation: fix timeout handling
21+
* Contributors: Robert Haschke
22+
23+
0.1.1 (2023-02-15)
24+
------------------
25+
* Resort to MoveIt's python tools
26+
* Provide ComputeIK.ik_frame as full PoseStamped
27+
* Fixed build farm issues
28+
29+
* Removed unused eigen_conversions includes
30+
* Fixed odr compiler warning on Buster
31+
* Fixed missing dependency declarations
32+
* Contributors: Robert Haschke
33+
534
0.1.0 (2023-02-02)
635
------------------
736
* Initial release

core/doc/basics.rst

+26-9
Original file line numberDiff line numberDiff line change
@@ -1,30 +1,47 @@
11
Basic Concepts
22
==============
33

4-
The fundamental idea of MTC is that complex motion planning problems can be composed into a set of simpler subproblems. The top-level planning problem is specified as a Task while all subproblems are specified by Stages. Stages can be arranged in any arbitrary order and hierarchy only limited by the individual stages types. The order in which stages can be arranged is restricted by the direction in which results are passed. There are three possible stages relating to the result flow: generator, propagator, and connector stages:
4+
The fundamental idea of MTC is that complex motion planning problems can be composed into a set of simpler subproblems. The top-level planning problem is specified as a Task while all subproblems are specified by Stages. Stages can be arranged in any arbitrary order and hierarchy only limited by the individual stages types. The order in which stages can be arranged is restricted by the direction in which results are passed. There are three possible stage types w.r.t. their data flow: generators, propagators, and connector stages:
55

66
.. glossary::
77

88
Generators
9-
compute their results independently of their neighbor stages and pass them in both directions, backwards and forwards. An example is an IK sampler for geometric poses where approaching and departing motions (neighbor stages) depend on the solution.
9+
compute their results independently of their neighboring stages and pass them in both directions, backwards and forwards. Examples include pose generators, e.g. for grasping or placing, as well as ``ComputeIK``, which computes IK solutions for Cartesian targets. neighboring stages can continue processing from the generated states. The most important generator stage, however, is ``CurrentState``, which provides the current robot state as the starting point for a planning pipeline.
1010

1111
Propagators
12-
receive the result of one neighbor stage, solve a subproblem and then propagate their result to the neighbor on the opposite site. Depending on the implementation, propagating stages can pass solutions forward, backward or in both directions separately. An example is a stage that computes a Cartesian path based on either a start or a goal state.
12+
receive the result of *one* neighboring stage as input, plan towards a goal state, and then propagate their result to the opposite interface site. Propagating stages can receive their input on either interface, begin or end. The flow of information (forwards or backwards) is determined by the input interface of the stage. An example is a stage that computes a Cartesian path based on either a start or a goal state.
1313

1414
Connectors
15-
do not propagate any results, but rather attempt to bridge the gap between the resulting states of both neighbors. An example is the computation of a free-motion plan from one given state to another.
15+
do not propagate any results, but rather attempt to bridge the gap between the resulting states of both its neighboring stages. It receives input states from both, the begin and end interface and attempts to connect them via a suitable motion plan. Obviously, any pair of input states needs to be *compatible*, i.e. their states (including collision and attached objects as well as joint poses) need to match except for those joints that are part of the given planning group.
1616

17-
Additional to the order types, there are different hierarchy types allowing to encapsulate subordinate stages. Stages without subordinate stages are called primitive stages, higher-level stages are called container stages. There are three container types:
17+
Processing starts from generator stages, expands via propagators, and finally connects partial solution sequences via connector stages.
18+
Obviously, there exist limitations on how stages can be connected to each other. For example, two generator stages cannot occur in sequence as they would both attempt to *write* into their interfaces, but non of them is actually *reading*. Same applies for two connectors in a row: they would both attempt to read, while no stage is actually writing.
19+
The compatibility of stages is automatically checked once before planning by ``Task::init()``.
20+
21+
To compose a planning pipeline from multiple seemingly independent parts, for example grasping an object and placing it at a new location, one needs to break the typical linear pipeline structure: the place pose is another generator stage (additionally to the ``CurrentState`` stage we are starting from) serving as a seed for the placing sub solution. However, this stage is not completely independent from the grasping sub solution: it should continue where grasping left off, namely with the grasped object attached to the gripper. To convey this state information, the place pose generator should inherit from ``MonitoringGenerator``, which monitors the solutions of another stage in the pipeline in fast-forwards them for further processing in the dependent stage.
22+
23+
In order to hierarchically organize planning pipelines and to allow for reuse of sub pipelines, e.g. for grasping or placing, one can encapsulate stages within various containers.
24+
Stages without children are called primitive stages. We provide three types of containers:
1825

1926
.. glossary::
2027

2128
Wrappers
22-
encapsulate a single subordinate stage and modify or filter the results. For example, a filter stage that only accepts solutions of its child stage that satisfy a certain constraint can be realized as a wrapper. Another standard use of this type includes the IK wrapper stage, which generates inverse kinematics solutions based on planning scenes annotated with a pose target property.
29+
encapsulate a single subordinate stage and modify or filter its results. For example, a filter stage that only accepts solutions of its child stage that satisfy a certain constraint can be realized as a wrapper. Another standard use of this type includes the IK wrapper stage, which generates inverse kinematics solutions based on planning scenes annotated with a pose target property.
2330

24-
Serial Containers
31+
Serial containers
2532
hold a sequence of subordinate stages and only consider end-to-end solutions as results. An example is a picking motion that consists of a sequence of coherent steps.
2633

27-
Parallel Containers
28-
combine set of subordinate stages and can be used for passing the best of alternative results, running fallback solvers or for merging multiple independent solutions. Examples are running alternative planners for a free-motion plan, picking objects with the right hand or with the left hand as a fallback, or moving the arm and opening the gripper at the same time.
34+
Parallel containers
35+
consider the solutions of all their children as feasible. Different sub types are available, namely:
36+
37+
``Alternative`` container
38+
processes all children simultaneously (currently in a round-robin fashion). For example, one could plan a grasping sequence for a left and right arm in parallel if the actual choice of the arm doesn't matter for the task.
39+
40+
``Fallback`` container
41+
processes their children sequentially: only if the current child has exhausted all its solution candidates (and didn't produce any feasible solution), the next child is considered.
42+
Use this container, e.g. if you prefer grasping with the right arm, but allow falling back to the left if really needed.
43+
44+
``Merger`` container
45+
processes their children simultaneously and combine their solutions into an joint solution. It is assumed that children operate on disjoint joint model groups, e.g. the arm and the hand, such that their solution trajectories can be executed in parallel after being merged.
2946

3047
Stages not only support solving motion planning problems. They can also be used for all kinds of state transitions, as for instance modifying the planning scene. Combined with the possibility of using class inheritance it is possible to construct very complex behavior while only relying on a well-structured set of primitive stages.

core/doc/index.rst

+1
Original file line numberDiff line numberDiff line change
@@ -28,3 +28,4 @@ Organization of the documentation
2828
concepts
2929
howto
3030
api
31+
troubleshooting

core/doc/troubleshooting.rst

+31
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
.. _sec-troubleshooting:
2+
3+
Troubleshooting
4+
===============
5+
6+
``Task::init()`` reports mismatching interfaces
7+
-----------------------------------------------
8+
9+
Before planning, the planning pipeline is checked for consistency. Each stage type has a specific flow interface, e.g. generator-type stages write into both, their begin and end interface, propagator-type stages read from one and write to the opposite, and connector-type stages read from both sides. Obviously these interfaces need to match. If they don't, an ``InitStageException`` is thrown. Per default, this is not very verbose, but you can use the following code snippet to get some more info:
10+
11+
.. code-block:: c
12+
13+
try {
14+
task.plan();
15+
} catch (const InitStageException& e) {
16+
std::cerr << e << std::endl;
17+
throw;
18+
}
19+
20+
For example, the following pipeline:
21+
22+
- ↕ current
23+
- ⛓ connect
24+
- ↑ moveTo
25+
26+
throws the error: ``task pipeline: end interface (←) of 'moveto' does not match mine (→)``.
27+
28+
The validation process runs sequentially through a ``SerialContainer``. Here, ``current``, as a generator stage is compatible to ``connect``, writing to the interface read by ``connect``.
29+
``moveTo`` as a propagator can operate, in principle, forwards and backwards. By default, the operation direction is inferred automatically. Here, as ``connect`` requires a reading end-interface, moveTo should seemingly operate backwards. However, now the whole pipeline is incompatible to the enclosing container's interface: a task requires a generator-type interface as it generates solutions - there is no input interface to read from. Hence, the *reading* end interface (←) of ``moveto`` conflicts with a *writing* end interface of the task.
30+
31+
Obviously, in a ``ParallelContainer`` all (direct) children need to share a common interface.

core/include/moveit/python/python_tools/geometry_msg_types.h

-27
This file was deleted.

core/include/moveit/python/python_tools/ros_init.h

-31
This file was deleted.

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

+5-2
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,14 @@
11
#pragma once
22

3-
#include <moveit/python/python_tools/ros_types.h>
4-
#include <moveit/python/python_tools/geometry_msg_types.h>
3+
#include <pybind11/smart_holder.h>
4+
#include <moveit/python/pybind_rosmsg_typecasters.h>
55
#include <moveit/task_constructor/properties.h>
66
#include <boost/any.hpp>
77
#include <typeindex>
88

9+
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Property)
10+
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::PropertyMap)
11+
912
namespace moveit {
1013
namespace python {
1114

core/include/moveit/task_constructor/container.h

+1
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ class ContainerBase : public Stage
7676

7777
virtual bool canCompute() const = 0;
7878
virtual void compute() = 0;
79+
void explainFailure(std::ostream& os) const override;
7980

8081
/// called by a (direct) child when a new solution becomes available
8182
virtual void onNewSolution(const SolutionBase& s) = 0;

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

+4-2
Original file line numberDiff line numberDiff line change
@@ -56,8 +56,10 @@ class CartesianPath : public PlannerInterface
5656
void setJumpThreshold(double jump_threshold) { setProperty("jump_threshold", jump_threshold); }
5757
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }
5858

59-
void setMaxVelocityScaling(double factor) { setProperty("max_velocity_scaling_factor", factor); }
60-
void setMaxAccelerationScaling(double factor) { setProperty("max_acceleration_scaling_factor", factor); }
59+
[[deprecated("Replace with setMaxVelocityScalingFactor")]] // clang-format off
60+
void setMaxVelocityScaling(double factor) { setMaxVelocityScalingFactor(factor); }
61+
[[deprecated("Replace with setMaxAccelerationScalingFactor")]] // clang-format off
62+
void setMaxAccelerationScaling(double factor) { setMaxAccelerationScalingFactor(factor); }
6163

6264
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
6365

0 commit comments

Comments
 (0)