The MoveIt 2 journey (part 1): porting and understanding moveit_core

The MoveIt 2 motion planning framework is an open source software for motion planning, manipulation, 3D perception, kinematics, control and navigation. It’s built on top of the Robot Operating System (ROS 2) and altogether, remains the third most popular package in the ROS world. MoveIt provides an easy-to-use platform for developing advanced robotics applications, evaluating new robot designs, and building integrated robotics products for industrial, commercial, R&D, and other domains. MoveIt 2 is is the ROS 2 version of MoveIt.

This is the second of a series of articles to describe our learning experience and contributions with the MoveIt 2 and ROS 2 communities. The complete series is listed below:

  1. why MoveIt 2?
  2. porting and understanding moveit_core (this one)

In this second part we will discuss moveit_core, one of the most relevant elements of the MoveIt motion planning framework. moveit_core includes the core libraries used by MoveIt 2. Mainly and as described on its original README:

  • representation of kinematic models
  • collision detection interfaces and implementations
  • interfaces for kinematic solver plugins
  • interfaces for motion planning plugins
  • interfaces for controllers and sensors

These capabilities do not depend on ROS 2 (except ROS messages) and can be used independently.

Status of the port

At the time of writing, here’s the actual status of the port (available here):

Update/setup infrastructure for development
Dependencies on other packages
Convert moveit_core packages to ROS 2.0
  • Convert moveit_core packages to ROS 2.0
  • version
  • macros
  • backtrace
  • exceptions
  • profiler
  • logging
  • background_processing
  • kinematics_base
  • controller_manager
  • sensor_manager
  • robot_model
  • transforms
  • robot_state
  • robot_trajectory
  • collision_detection
  • collision_detection_fcl
  • kinematic_constraints
  • planning_scene
  • constraint_samplers
  • planning_interface
  • planning_request_adapter
  • trajectory_processing
  • distance_field
  • collision_distance_field
  • kinematics_metrics
  • dynamics_solver
  • utils
Other moveit packages (e.g. moveit_ros, ...)
Necessary for a Minimal Working Example
  • Necessary for a Minimal Working Example (This list can vary, they are >the initial includes for the planning_interface/move_group_interface that >is what we need for a plan and execute)
  • moveit_ros_perception
    • occupancy_map_monitor
  • move_group
    • capability_names
  • planning
    • collision_plugin_loader
    • planning_scene_monitor
      • current_state_monitor
      • planning_scene_monitor
      • trajectory_monitor
    • trajectory_execution_manager
      • trajectory_execution_manager
    • common_planning_interface_objects
      • common_objects
  • planning_interface
    • planning_scene_interface
      • planning_scene_interface
  • moveit_ros_manipulation
    • move_group_pick_place_capability
      • capability_names.h
New features in ROS 2.0
  • New features in ROS 2.0
  • Migrate plugin architecture to ROS2 nodelets
Documentation - [ ] Documentation - [ ] Tutorials for MoveIt2 - [ ] Create tutorial on using ros1/ros2 bridge to support ros1 hardware >drivers - [ ] Move install instructions to moveit.ros.org
Major refactoring and divergence from moveit2 (not >started)
  • Major refactoring and divergence from moveit2
  • Run ROS2 C++ and python linters
  • Delete excesses packages that are left over from rosbuild stacks: moveit_runtime, moveit_plugins, moveit_ros
  • Rename non-package folders:
    • rename moveit_planners to planners
    • rename moveit_plugins to controller_interfaces
  • Restructure folder layout of moveit repo:
    • flatten moveit_ros folder to root of repo
    • rename all moveit_ros folders with moveit_ros prefix
  • Rename major classes
    • ControllerManagers become ControllerInterfaces
    • Rename related packages
  • Merge repos:
    • moveit 9.6 MB
    • moveit_task_constructor
    • moveit_tutorials 28.6 MB
    • moveit_msgs
    • moveit_resources 61 MB
    • moveit_visual_tools
    • moveit_advanced?
    • DELETE: moveit_kinematics_tests
  • Remove large binaries from moveit repo
  • Add gitlfs?

Continuous integration and unit tests

We are developing both in both OS X and Linux. To get initial support for both platforms and ensure good development practices, we decided to set up some initial (simple) CI with Travis CI multi-OS (enable OS X also) · Issue #4 · AcutronicRobotics/moveit2 · GitHub for both, Linux and OS X. This CI worked nicely and basically replicated the flow of the official installation instructions provided by Open Robotics in Travis. Unfortunately, this never got merged and we instead moved into a more sophisticated CI the moveit team has been maintaining: GitHub - ros-planning/moveit_ci: Continuous Integration for MoveIt.

At the time of writing and while efforts have been put into enabling this for ROS 2 (credit to MoveIt maintainers), the moveit_ci isn’t yet ready to process moveit_core and other modules of moveit2. In an attempt to get aligned, our team has been working on an extension of moveit_ci particularized for our infrastructure which successfully builds and tests moveit_core and all other packages we’re currently porting. This work is available at GitHub - AcutronicRobotics/moveit2_ci: Continuous Integration for MoveIt 2 and hopefully, it’ll eventually be merged and integrated https://github.com/ros-planning/moveit_ci/pull/56.

Porting moveit_core

At the time of writing, a first version of moveit_core is available and ported to ROS 2 in our development fork[1]. Most moveit_core submodules depend on a number of other ROS packages that had to be similarly ported to ROS 2 and fetched into a workspace:

To ensure alignment with the community, Pull Requests have been submitted to MoveIt 2 official repository for the different moveit_core submodules as follows:

version (status: merged)

A simple module to determine the version of MoveIt 2
macros (status: merged)

A variety of macro definitions used across MoveIt 2.
backtrace (status: merged)

Module to fetch the backtrace, when possible
exceptions (status: merged)

MoveIt 2-specific exception definitions.
profiler (status: merged)

Simple thread-safe tool for counting time spent in various chunks of code.
background_processing (in review)

Provides a simple class that provides an API for executing background jobs. A queue of jobs is created and the specified jobs are executed in order, one at a time.
kinematics_base (in review)

defines a base API for forward and inverse kinematics. This API gets extended by other classes implementing IK and FK solvers.
controller_manager (status: merged)

MoveIt 2 does not enforce how controllers are implemented. Instead, to make your controllers usable by MoveIt, MoveItControllerManager interface needs to be implemented. The main purpose of this interface is to expose the set of known controllers and potentially to allow activating and deactivating them, if multiple controllers are available.
sensor_manager (status: merged)

Define the frame of reference and the frustum of a sensor (usually this is a visual sensor)
robot_model (in review)

Definition of kinematic models. This includes the complete robot model but also individual joints, links, etc.
transforms (status: merged)

This submodule contains mostly the Transform class which provides an implementation of a snapshot of a transform tree that can be easily queried for transforming different quantities.
robot_state (status: in review )

Representation of a robot’s state. This includes position, velocity, acceleration and effort.
robot_trajectory (status: in review)

Maintain a sequence of waypoints and the time durations between these waypoints
collision_detection (status: in review )

Generic interface to collision detection. Facilitates tools to check for self-collisions or collisions with other robots (CollisionRobot class) or with the environment (CollisionWorld class).
collision_detection_fcl (status: in review )

Another library for collision detection based on the Flexible Collision Library (FCL) library.
kinematic_constraints (status: in review )

Representation and evaluation of kinematic constraints
planning_scene (status: in review )

module for representing planning contexts. Maintains the representation of the environment as seen by a planning instance.
constraint_samplers (status: in review )

contains methods for generating samples based on a constraint or set of constraints. It is intended for use by any algorithm that requires a constraint-aware sampling strategy.
planning_interface (status: in review )

Base class for MoveIt! planners
planning_request_adapter (status: in review )

Generic interface to adapting motion planning requests. Adapt the planning request (if needed) for different planners.
trajectory_processing (status: in review )

Tools for processing a given trajectory
distance_field (status: in review )

Module that holds classes that generate distance fields, dense 3D representations containing the distance to the nearest obstacles.
collision_distance_field (status: in review )

Distance Field collision tools and methods
kinematics_metrics (status: in review )

Compute different kinds of metrics for kinematics evaluation. Currently includes manipulability.
dynamics_solver (status: in review )

Solver that computes the required torques given a joint configuration, velocities, accelerations and external wrenches acting on the links of a robot
utils (status: in review )

Utilities including convenience functions and classes used for making simple robot models for testing or locale-agnostic conversion functions from floating point numbers to strings

Lots of possibilities to contribute

Our investment in the MoveIt 2 project is made with a vision of long term. We hope to be involved with it for a very, very long time. However, nowadays, we have very limited resources and our commitment has been to put effort into contributing to deliver a first working prototype of MoveIt 2 with MARA. We hope this will drive the community to get involved faster in the project. At the same time, this means that sometimes we won’t fully port all dependencies nor all modules within each package. We’ll aim to port the minimum set of packages for creating a demonstration and then re-iterate on all the MoveIt 2 code, improving things on spirals as much as time and our resources allow for it.

There’s still work to do including finalizing the port of unit tests or optimizing certain parts of the code with new ROS 2 primitives. If you have bandwidth to contribute and would like to get involved in a new fast growing project, we encourage you to jump in to any of those open pull requests or to create a new one with your contribution.

How to reproduce the work so far

In order to facilitate the involvement of third parties, we’ve generated simple instructions on how to reproduce our current setup in OS X and Linux:

Moreover, we’ll be generating tutorials and guides for MoveIt 2. Furthermore, to reproduce the CI work locally, do so from the instructions at GitHub - AcutronicRobotics/moveit2_ci: Continuous Integration for MoveIt 2.

Acknowledgements

We’d like to credit our partners at PickNik for their support in the process and the MoveIt maintainers. Similarly, we’d like to thank William Woodall, Dirk Thomas and Tully Foote for their input.

References

6 Likes

I appreciate your effort in creating MoveIt 2! I think a lot of groups have been waiting on MoveIt 2 before switching to ROS2.

3 Likes

Great effort. BTW, why did we drop “!” :smiley: