Skip to content

Commit fe169e0

Browse files
committed
Merge branch 'ros2' into ros2-new
2 parents b8b1bd6 + 46a0f12 commit fe169e0

File tree

117 files changed

+1152
-993
lines changed

Some content is hidden

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

117 files changed

+1152
-993
lines changed

.github/workflows/ci.yaml

+6-5
Original file line numberDiff line numberDiff line change
@@ -19,26 +19,27 @@ jobs:
1919
fail-fast: false
2020
matrix:
2121
env:
22+
# - IMAGE: rolling-source
23+
# NAME: ccov
24+
# TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"
2225
- IMAGE: rolling-source
23-
NAME: ccov
24-
TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"
2526
- IMAGE: rolling-source
2627
CLANG_TIDY: pedantic
27-
- IMAGE: rolling-source
28+
- IMAGE: jazzy-source
2829
NAME: asan
2930
# Add fast_unwind_on_malloc=0 to fix stacktraces being too short or do not make sense
3031
# see https://github.com/google/sanitizers/wiki/AddressSanitizer
3132
# Disable alloc/dealloc mismatch warnings: https://github.com/ros2/rclcpp/pull/1324
3233
DOCKER_RUN_OPTS: >-
33-
-e PRELOAD=libasan.so.5
34+
-e PRELOAD=libasan.so.8
3435
-e LSAN_OPTIONS="suppressions=$PWD/.github/workflows/lsan.suppressions,fast_unwind_on_malloc=0"
3536
-e ASAN_OPTIONS="new_delete_type_mismatch=0,alloc_dealloc_mismatch=0"
3637
TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1 -g"
3738

3839
env:
3940
CLANG_TIDY_ARGS: -quiet -export-fixes ${{ github.workspace }}/.work/clang-tidy-fixes.yaml
4041
DOCKER_IMAGE: moveit/moveit2:${{ matrix.env.IMAGE }}
41-
UNDERLAY: /root/ws_moveit/install
42+
UNDERLAY: ${{ endsWith(matrix.env.IMAGE, '-source') && '/root/ws_moveit/install' || ''}}
4243
# TODO: Port to ROS2
4344
# DOWNSTREAM_WORKSPACE: "github:ubi-agni/mtc_demos#master github:TAMS-Group/mtc_pour#master"
4445
TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Release

.github/workflows/prerelease.yaml

+8-8
Original file line numberDiff line numberDiff line change
@@ -5,24 +5,24 @@ name: pre-release
55

66
on:
77
workflow_dispatch:
8+
inputs:
9+
ROS_DISTRO:
10+
type: string
11+
required: true
12+
description: 'ROS distribution codename:'
13+
default: noetic
814

915
permissions:
1016
contents: read # to fetch code (actions/checkout)
1117

1218
jobs:
1319
default:
14-
strategy:
15-
matrix:
16-
distro: [noetic]
17-
1820
env:
19-
# https://github.com/ros-industrial/industrial_ci/issues/666
20-
BUILDER: catkin_make_isolated
21-
ROS_DISTRO: ${{ matrix.distro }}
21+
ROS_DISTRO: ${{ inputs.ROS_DISTRO }}
2222
PRERELEASE: true
2323
BASEDIR: ${{ github.workspace }}/.work
2424

25-
name: "${{ matrix.distro }}"
25+
name: "${{ inputs.ROS_DISTRO }}"
2626
runs-on: ubuntu-latest
2727
steps:
2828
- name: "Free up disk space"

.gitmodules

+3
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

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ This repository provides the following branches:
2424

2525
## Tutorial
2626

27-
We provide a tutorial for a pick-and-place pipeline without bells & whistles [as part of the MoveIt tutorials](https://ros-planning.github.io/moveit_tutorials/doc/moveit_task_constructor/moveit_task_constructor_tutorial.html).
27+
We provide a tutorial for a pick-and-place pipeline without bells & whistles [as part of the MoveIt tutorials](https://moveit.github.io/moveit_tutorials/doc/moveit_task_constructor/moveit_task_constructor_tutorial.html).
2828

2929
## Roadmap
3030

capabilities/CMakeLists.txt

+8
Original file line numberDiff line numberDiff line change
@@ -3,11 +3,14 @@ project(moveit_task_constructor_capabilities)
33

44
find_package(ament_cmake REQUIRED)
55

6+
find_package(fmt REQUIRED)
67
find_package(Boost REQUIRED)
78
find_package(moveit_common REQUIRED)
89
moveit_package()
910
find_package(moveit_core REQUIRED)
1011
find_package(moveit_ros_move_group REQUIRED)
12+
find_package(moveit_ros_planning REQUIRED)
13+
find_package(moveit_task_constructor_core REQUIRED)
1114
find_package(moveit_task_constructor_msgs REQUIRED)
1215
find_package(pluginlib REQUIRED)
1316
find_package(rclcpp_action REQUIRED)
@@ -18,9 +21,12 @@ add_library(${PROJECT_NAME} SHARED
1821
)
1922
ament_target_dependencies(${PROJECT_NAME}
2023
Boost
24+
fmt
2125
rclcpp_action
2226
moveit_core
2327
moveit_ros_move_group
28+
moveit_ros_planning
29+
moveit_task_constructor_core
2430
moveit_task_constructor_msgs
2531
)
2632

@@ -31,6 +37,8 @@ install(TARGETS ${PROJECT_NAME}
3137
pluginlib_export_plugin_description_file(moveit_ros_move_group capabilities_plugin_description.xml)
3238
ament_export_dependencies(moveit_core)
3339
ament_export_dependencies(moveit_ros_move_group)
40+
ament_export_dependencies(moveit_ros_planning)
41+
ament_export_dependencies(moveit_task_constructor_core)
3442
ament_export_dependencies(moveit_task_constructor_msgs)
3543
ament_export_dependencies(pluginlib)
3644
ament_export_dependencies(rclcpp_action)

capabilities/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212

1313
<buildtool_depend>ament_cmake</buildtool_depend>
1414

15+
<depend>fmt</depend>
1516
<depend>moveit_core</depend>
1617
<depend>moveit_ros_move_group</depend>
1718
<depend>moveit_ros_planning</depend>

capabilities/src/execute_task_solution_capability.cpp

+8-9
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,7 @@
4343
#include <moveit/move_group/capability_names.h>
4444
#include <moveit/robot_state/conversions.h>
4545
#include <moveit/utils/message_checks.h>
46-
#include <moveit/moveit_cpp/moveit_cpp.h>
47-
48-
#include <boost/algorithm/string/join.hpp>
46+
#include <fmt/format.h>
4947

5048
namespace {
5149

@@ -164,8 +162,8 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
164162
if (!joint_names.empty()) {
165163
group = findJointModelGroup(*model, joint_names);
166164
if (!group) {
167-
RCLCPP_ERROR_STREAM(LOGGER, "Could not find JointModelGroup that actuates {"
168-
<< boost::algorithm::join(joint_names, ", ") << "}");
165+
RCLCPP_ERROR_STREAM(LOGGER, fmt::format("Could not find JointModelGroup that actuates {{{}}}",
166+
fmt::join(joint_names, ", ")));
169167
return false;
170168
}
171169
RCLCPP_DEBUG(LOGGER, "Using JointModelGroup '%s' for execution", group->getName().c_str());
@@ -184,11 +182,12 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
184182
exec_traj.controller_name = sub_traj.execution_info.controller_names;
185183

186184
/* TODO add action feedback and markers */
187-
exec_traj.effect_on_success = [this,
188-
&scene_diff = const_cast<::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff),
185+
exec_traj.effect_on_success = [this, &scene_diff = const_cast<::moveit_msgs::PlanningScene&>(sub_traj.scene_diff),
189186
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
190-
scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
191-
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
187+
// Never modify joint state directly (only via robot trajectories)
188+
scene_diff.robot_state.joint_state = sensor_msgs::JointState();
189+
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::MultiDOFJointState();
190+
scene_diff.robot_state.is_diff = true; // silent empty JointState msg error
192191

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

core/CMakeLists.txt

+5-2
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,15 @@ project(moveit_task_constructor_core)
44
find_package(ament_cmake REQUIRED)
55

66
find_package(Boost REQUIRED)
7+
find_package(fmt REQUIRED)
78
find_package(geometry_msgs REQUIRED)
89
find_package(moveit_common REQUIRED)
910
moveit_package()
1011
find_package(moveit_core REQUIRED)
1112
find_package(moveit_ros_planning REQUIRED)
1213
find_package(moveit_ros_planning_interface REQUIRED)
1314
find_package(moveit_task_constructor_msgs REQUIRED)
15+
find_package(py_binding_tools REQUIRED)
1416
find_package(rclcpp REQUIRED)
1517
find_package(rviz_marker_tools REQUIRED)
1618
find_package(tf2_eigen REQUIRED)
@@ -25,8 +27,8 @@ add_compile_options(-fvisibility-inlines-hidden)
2527
set(PROJECT_INCLUDE ${CMAKE_CURRENT_SOURCE_DIR}/include/moveit/task_constructor)
2628

2729
add_subdirectory(src)
28-
# TODO: enable python wrapper
29-
#add_subdirectory(python)
30+
ament_python_install_package(moveit PACKAGE_DIR python/moveit)
31+
add_subdirectory(python)
3032
add_subdirectory(test)
3133

3234
install(DIRECTORY include/ DESTINATION include
@@ -41,6 +43,7 @@ ament_export_dependencies(moveit_core)
4143
ament_export_dependencies(moveit_ros_planning)
4244
ament_export_dependencies(moveit_ros_planning_interface)
4345
ament_export_dependencies(moveit_task_constructor_msgs)
46+
ament_export_dependencies(py_binding_tools)
4447
ament_export_dependencies(rclcpp)
4548
ament_export_dependencies(rviz_marker_tools)
4649
ament_export_dependencies(tf2_eigen)

core/doc/tutorials/properties.rst

-5
Original file line numberDiff line numberDiff line change
@@ -97,11 +97,6 @@ You can obtain a reference to the the PropertyMap of a stage like so
9797
:start-after: [propertyTut10]
9898
:end-before: [propertyTut10]
9999

100-
.. literalinclude:: ../../../demo/scripts/properties.py
101-
:language: python
102-
:start-after: [propertyTut11]
103-
:end-before: [propertyTut11]
104-
105100

106101
As mentioned, each stage contains a PropertyMap.
107102
Stages communicate to each other via their interfaces.

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

-90
This file was deleted.

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

+4-4
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#pragma once
22

33
#include <pybind11/smart_holder.h>
4-
#include <moveit/python/pybind_rosmsg_typecasters.h>
4+
#include <py_binding_tools/ros_msg_typecasters.h>
55
#include <moveit/task_constructor/properties.h>
66
#include <boost/any.hpp>
77
#include <typeindex>
@@ -35,12 +35,12 @@ class PropertyConverter : protected PropertyConverterBase
3535
static boost::any fromPython(const pybind11::object& po) { return pybind11::cast<T>(po); }
3636

3737
template <class Q = T>
38-
typename std::enable_if<ros::message_traits::IsMessage<Q>::value, std::string>::type rosMsgName() {
39-
return ros::message_traits::DataType<T>::value();
38+
typename std::enable_if<rosidl_generator_traits::is_message<Q>::value, std::string>::type rosMsgName() {
39+
return rosidl_generator_traits::name<Q>();
4040
}
4141

4242
template <class Q = T>
43-
typename std::enable_if<!ros::message_traits::IsMessage<Q>::value, std::string>::type rosMsgName() {
43+
typename std::enable_if<!rosidl_generator_traits::is_message<Q>::value, std::string>::type rosMsgName() {
4444
return std::string();
4545
}
4646
};

core/include/moveit/task_constructor/container.h

+4
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,10 @@ class ContainerBase : public Stage
5151
PRIVATE_CLASS(ContainerBase)
5252
using pointer = std::unique_ptr<ContainerBase>;
5353

54+
/// Explicitly enable/disable pruning
55+
void setPruning(bool pruning) { setProperty("pruning", pruning); }
56+
bool pruning() const { return properties().get<bool>("pruning"); }
57+
5458
size_t numChildren() const;
5559
Stage* findChild(const std::string& name) const;
5660
Stage* operator[](int index) const;

core/include/moveit/task_constructor/cost_terms.h

+8
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ class LambdaCostTerm : public TrajectoryCostTerm
9595
LambdaCostTerm(const SubTrajectorySignature& term);
9696
LambdaCostTerm(const SubTrajectoryShortSignature& term);
9797

98+
using TrajectoryCostTerm::operator();
9899
double operator()(const SubTrajectory& s, std::string& comment) const override;
99100

100101
protected:
@@ -132,6 +133,8 @@ class PathLength : public TrajectoryCostTerm
132133
PathLength(std::vector<std::string> joints);
133134
/// Limit measurements to given joints and use given weighting
134135
PathLength(std::map<std::string, double> j) : joints(std::move(j)) {}
136+
137+
using TrajectoryCostTerm::operator();
135138
double operator()(const SubTrajectory& s, std::string& comment) const override;
136139

137140
std::map<std::string, double> joints; //< joint weights
@@ -145,6 +148,8 @@ class DistanceToReference : public TrajectoryCostTerm
145148
std::map<std::string, double> w = std::map<std::string, double>());
146149
DistanceToReference(const std::map<std::string, double>& ref, Mode m = Mode::AUTO,
147150
std::map<std::string, double> w = std::map<std::string, double>());
151+
152+
using TrajectoryCostTerm::operator();
148153
double operator()(const SubTrajectory& s, std::string& comment) const override;
149154

150155
moveit_msgs::msg::RobotState reference;
@@ -156,6 +161,7 @@ class DistanceToReference : public TrajectoryCostTerm
156161
class TrajectoryDuration : public TrajectoryCostTerm
157162
{
158163
public:
164+
using TrajectoryCostTerm::operator();
159165
double operator()(const SubTrajectory& s, std::string& comment) const override;
160166
};
161167

@@ -167,6 +173,7 @@ class LinkMotion : public TrajectoryCostTerm
167173

168174
std::string link_name;
169175

176+
using TrajectoryCostTerm::operator();
170177
double operator()(const SubTrajectory& s, std::string& comment) const override;
171178
};
172179

@@ -191,6 +198,7 @@ class Clearance : public TrajectoryCostTerm
191198

192199
std::function<double(double)> distance_to_cost;
193200

201+
using TrajectoryCostTerm::operator();
194202
double operator()(const SubTrajectory& s, std::string& comment) const override;
195203
};
196204

0 commit comments

Comments
 (0)