Skip to content

Commit

Permalink
Merge branch 'main' into pr-moveit_configs_utils
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw committed Jan 20, 2022
2 parents 5144564 + 4c75dcf commit 56abbeb
Show file tree
Hide file tree
Showing 78 changed files with 2,792 additions and 63 deletions.
2,427 changes: 2,427 additions & 0 deletions Doxyfile

Large diffs are not rendered by default.

3 changes: 3 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@ See the [MoveItCpp Tutorial](https://moveit.picknik.ai/foxy/doc/moveit_cpp/movei
The [Move Group C++ Interface](https://moveit.picknik.ai/foxy/doc/move_group_interface/move_group_interface_tutorial.html) provides a simple launch file for running a MoveGroup setup.
You can test it using the MotionPlanning display in RViz or by implementing your own MoveGroupInterface application.

## Having Doxygen Reference Locally
See [How To Generate API Doxygen Reference Locally](https://moveit.picknik.ai/main/doc/how_to_guides/how_to_generate_api_doxygen_locally.html)

## Supporters

This open source project is maintained by supporters from around the world — see [MoveIt maintainers](https://moveit.ros.org/about/). Special thanks to contributor from Intel and Open Robotics.
Expand Down
3 changes: 3 additions & 0 deletions moveit/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package moveit
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>Meta package that contains all essential packages of MoveIt 2</description>
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
<maintainer email="tyler@picknik.ai">Tyler Weaver</maintainer>
Expand Down
5 changes: 5 additions & 0 deletions moveit_common/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package moveit_common
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
* Contributors: Abishalini

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_common</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>Common support functionality used throughout MoveIt</description>
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
<maintainer email="tyler@picknik.ai">Tyler Weaver</maintainer>
Expand Down
47 changes: 47 additions & 0 deletions moveit_core/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,53 @@
Changelog for package moveit_core
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Move background_processing (`#997 <https://github.com/ros-planning/moveit2/issues/997>`_)
* Fix boost linking errors for Windows (`#957 <https://github.com/ros-planning/moveit2/issues/957>`_)
* Delete backtrace hack (`#995 <https://github.com/ros-planning/moveit2/issues/995>`_)
* Use size_t for index variables (`#946 <https://github.com/ros-planning/moveit2/issues/946>`_)
* Remove moveit_build_options
* Merge https://github.com/ros-planning/moveit/commit/f3ac6070497da90da33551fc1dc3a68938340413
* Replace NULL with nullptr (`#961 <https://github.com/ros-planning/moveit2/issues/961>`_)
* Fixes `#841 <https://github.com/ros-planning/moveit2/issues/841>`_
* Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
* Add jerk to the robot model (`#683 <https://github.com/ros-planning/moveit2/issues/683>`_)
* Add jerk to the robot model
* Add joint limit parsing to a unit test
* Add jerk to computeVariableBoundsMsg and <<, too
* collision_distance_field: Fix undefined behavior vector insertion (`#942 <https://github.com/ros-planning/moveit2/issues/942>`_)
* Normalize incoming transforms (`#2920 <https://github.com/ros-planning/moveit2/issues/2920>`_)
* Normalize incoming transforms
* fixup: adapt comment according to review suggestion
Co-authored-by: Michael Görner <me@v4hn.de>
* Completely silent -Wmaybe-uninitialized
* Don't fail on -Wmaybe-uninitialized. Needs more analysis!
* Fix unused-variable warning
* Silent unused-function warnings
* Remove unused arguments from global_adjustment_factor()
Looks like, dt and x were passed originally to call fit_cubic_spline()
inside that function. However, later it was assumed that fit_cubic_spline()
was already called, rendering these parameters superfluous.
* Simplify API: Remove obviously unused arguments
* clang-tidy: fix unused parameter (critical cases)
This warnings should be considered in more detail (TODO).
Not using these arguments might be an actual bug.
* clang-tidy: fix unused parameter (uncritical cases)
These parameters aren't used for an obvious reason.
* moveit_build_options()
Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE,
and compiler options (namely warning flags) once.
Each package depending on moveit_core can use these via moveit_build_options().
* RobotState: write to correct array (`#2909 <https://github.com/ros-planning/moveit2/issues/2909>`_)
Not an actual bug because both arrays share the same memory.
As mentioned in https://github.com/ros-planning/moveit2/pull/683#pullrequestreview-780447848
* fix uninitialized orientation in default shape pose (`#2896 <https://github.com/ros-planning/moveit2/issues/2896>`_)
* Readability and consistency improvements in TOTG (`#2882 <https://github.com/ros-planning/moveit2/issues/2882>`_)
* Use std::fabs() everywhere
* Better comments
* Contributors: Abishalini, Akash, AndyZe, Michael Görner, Robert Haschke, Stephanie Eng, Tyler Weaver, andreas-botbuilt

2.3.2 (2021-12-29)
------------------

Expand Down
9 changes: 3 additions & 6 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,6 @@ find_package(rclcpp REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)

# Finds Boost Components
include(ConfigExtras.cmake)

find_package(PkgConfig REQUIRED)
pkg_check_modules(LIBFCL REQUIRED "fcl>=0.5.0")
# replace LIBFCL_LIBRARIES with full paths to the libraries
Expand Down Expand Up @@ -52,11 +49,13 @@ find_package(pluginlib REQUIRED)
# TODO: Port python bindings
# find_package(pybind11 REQUIRED)

# Finds Boost Components
include(ConfigExtras.cmake)

# Set target file path for version.h
set(VERSION_FILE_PATH ${CMAKE_BINARY_DIR}/include)

set(THIS_PACKAGE_INCLUDE_DIRS
background_processing/include
exceptions/include
collision_detection/include
collision_detection_fcl/include
Expand Down Expand Up @@ -87,7 +86,6 @@ set(THIS_PACKAGE_INCLUDE_DIRS
)

set(THIS_PACKAGE_LIBRARIES
moveit_background_processing
moveit_butterworth_filter
moveit_collision_distance_field
moveit_collision_detection
Expand Down Expand Up @@ -157,7 +155,6 @@ message(STATUS " *** Building MoveIt ${MOVEIT_VERSION} ***")
configure_file("version/version.h.in" "${VERSION_FILE_PATH}/moveit/version.h")
install(FILES "${VERSION_FILE_PATH}/moveit/version.h" DESTINATION include/moveit)

add_subdirectory(background_processing)
add_subdirectory(collision_distance_field)
add_subdirectory(constraint_samplers)
add_subdirectory(controller_manager)
Expand Down
12 changes: 0 additions & 12 deletions moveit_core/background_processing/CMakeLists.txt

This file was deleted.

1 change: 0 additions & 1 deletion moveit_core/distance_field/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
tf2_eigen
OCTOMAP
)
target_link_libraries(${MOVEIT_LIB_NAME} Boost::iostreams)

install(DIRECTORY include/ DESTINATION include)

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_core</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>Core libraries used by MoveIt</description>

<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ install(DIRECTORY include/ DESTINATION include)
find_package(ament_index_cpp REQUIRED)
set(MOVEIT_TEST_LIB_NAME moveit_test_utils)
add_library(${MOVEIT_TEST_LIB_NAME} SHARED src/robot_model_test_utils.cpp)
target_link_libraries(${MOVEIT_TEST_LIB_NAME} moveit_robot_model Boost::regex)
target_link_libraries(${MOVEIT_TEST_LIB_NAME} moveit_robot_model)
ament_target_dependencies(${MOVEIT_TEST_LIB_NAME}
ament_index_cpp
Boost
Expand Down
11 changes: 11 additions & 0 deletions moveit_kinematics/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,17 @@
Changelog for package moveit_kinematics
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Fix IKFast test dependency (`#993 <https://github.com/ros-planning/moveit2/issues/993>`_)
* Replace NULL with nullptr (`#961 <https://github.com/ros-planning/moveit2/issues/961>`_)
* Fixes `#841 <https://github.com/ros-planning/moveit2/issues/841>`_
* moveit_build_options()
Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE,
and compiler options (namely warning flags) once.
Each package depending on moveit_core can use these via moveit_build_options().
* Contributors: Henning Kayser, Robert Haschke, Stephanie Eng

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_kinematics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_kinematics</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>Package for all inverse kinematics solvers in MoveIt</description>

<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
Expand Down
8 changes: 8 additions & 0 deletions moveit_planners/chomp/chomp_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package chomp_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* moveit_build_options()
Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE,
and compiler options (namely warning flags) once.
Each package depending on moveit_core can use these via moveit_build_options().
* Contributors: Robert Haschke

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_planners_chomp</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>The interface for using CHOMP within MoveIt</description>

<maintainer email="chitt@live.in">Chittaranjan Srinivas Swaminathan</maintainer>
Expand Down
10 changes: 10 additions & 0 deletions moveit_planners/chomp/chomp_motion_planner/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@
Changelog for package chomp_motion_planner
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Replace NULL with nullptr (`#961 <https://github.com/ros-planning/moveit2/issues/961>`_)
* Fixes `#841 <https://github.com/ros-planning/moveit2/issues/841>`_
* moveit_build_options()
Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE,
and compiler options (namely warning flags) once.
Each package depending on moveit_core can use these via moveit_build_options().
* Contributors: Robert Haschke, Stephanie Eng

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_motion_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>chomp_motion_planner</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>chomp_motion_planner</description>

<maintainer email="chitt@live.in">Chittaranjan Srinivas Swaminathan</maintainer>
Expand Down
8 changes: 8 additions & 0 deletions moveit_planners/chomp/chomp_optimizer_adapter/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package moveit_chomp_optimizer_adapter
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* moveit_build_options()
Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE,
and compiler options (namely warning flags) once.
Each package depending on moveit_core can use these via moveit_build_options().
* Contributors: Robert Haschke

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_optimizer_adapter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<package format="2">
<name>moveit_chomp_optimizer_adapter</name>
<description>MoveIt planning request adapter utilizing chomp for solution optimization</description>
<version>2.3.2</version>
<version>2.4.0</version>
<maintainer email="raghavendersahdev@gmail.com">Raghavender Sahdev</maintainer>
<maintainer email="moveit_releasers@googlegroups.com">MoveIt Release Team</maintainer>

Expand Down
3 changes: 3 additions & 0 deletions moveit_planners/moveit_planners/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package moveit_planners
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/moveit_planners/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_planners</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>Meta package that installs all available planners for MoveIt</description>
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
<maintainer email="tyler@picknik.ai">Tyler Weaver</maintainer>
Expand Down
8 changes: 8 additions & 0 deletions moveit_planners/ompl/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package moveit_planners_ompl
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* moveit_build_options()
Declare common build options like CMAKE_CXX_STANDARD, CMAKE_BUILD_TYPE,
and compiler options (namely warning flags) once.
Each package depending on moveit_core can use these via moveit_build_options().
* Contributors: Robert Haschke

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/ompl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>moveit_planners_ompl</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>MoveIt interface to OMPL</description>
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
<maintainer email="tyler@picknik.ai">Tyler Weaver</maintainer>
Expand Down
15 changes: 15 additions & 0 deletions moveit_planners/pilz_industrial_motion_planner/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,21 @@
Changelog for package pilz_industrial_motion_planner
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Remove 'using namespace' from header files. (`#994 <https://github.com/ros-planning/moveit2/issues/994>`_)
* Fix missing ament_cmake_gtest dependency (`#981 <https://github.com/ros-planning/moveit2/issues/981>`_)
* Remove some Maintainers from Pilz Planner (`#971 <https://github.com/ros-planning/moveit2/issues/971>`_)
* Fix usage of boost placeholder (`#958 <https://github.com/ros-planning/moveit2/issues/958>`_)
* Merge https://github.com/ros-planning/moveit/commit/a0ee2020c4a40d03a48044d71753ed23853a665d
* Remove '-W*' options from cmake files (`#2903 <https://github.com/ros-planning/moveit2/issues/2903>`_)
* Add test for pilz planner with attached objects (`#2878 <https://github.com/ros-planning/moveit2/issues/2878>`_)
* Add test case for `#2824 <https://github.com/ros-planning/moveit2/issues/2824>`_
Co-authored-by: Cristian Beltran <cristianbehe@gmail.com>
Co-authored-by: Joachim Schleicher <joachimsl@gmx.de>
Co-authored-by: jschleicher <j.schleicher@pilz.de>
* Contributors: Abishalini, Cory Crean, Leroy Rügemer, Tyler Weaver, Wolf Vollprecht, cambel, jschleicher

2.3.2 (2021-12-29)
------------------

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/pilz_industrial_motion_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>pilz_industrial_motion_planner</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>MoveIt plugin to generate industrial trajectories PTP, LIN, CIRC and sequences thereof.</description>

<maintainer email="c.henkel@pilz.de">Christian Henkel</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package pilz_industrial_motion_planner_testutils
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Remove some Maintainers from Pilz Planner (`#971 <https://github.com/ros-planning/moveit2/issues/971>`_)
* Remove '-W*' options from cmake files (`#2903 <https://github.com/ros-planning/moveit2/issues/2903>`_)
* Contributors: Leroy Rügemer, jschleicher

2.3.2 (2021-12-29)
------------------

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>pilz_industrial_motion_planner_testutils</name>
<version>2.3.2</version>
<version>2.4.0</version>
<description>Helper scripts and functionality to test industrial motion generation</description>

<maintainer email="c.henkel@pilz.de">Christian Henkel</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package moveit_resources_prbt_ikfast_manipulator_plugin
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.4.0 (2022-01-20)
------------------
* Replace NULL with nullptr (`#961 <https://github.com/ros-planning/moveit2/issues/961>`_)
* Fixes `#841 <https://github.com/ros-planning/moveit2/issues/841>`_
* Contributors: Stephanie Eng

2.3.2 (2021-12-29)
------------------

Expand Down
Loading

0 comments on commit 56abbeb

Please sign in to comment.