diff --git a/.travis.yml b/.travis.yml index e127477ebf..8c4a259cac 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,32 +1,39 @@ -# Test build the MoveIt tutorials. Author: Dave Coleman -sudo: required -dist: xenial -language: ruby -rvm: - - 2.7 -python: - - "2.7" +# This config file for Travis CI utilizes https://github.com/ros-planning/moveit_ci/ package. +os: linux +dist: bionic # distro used by Travis, moveit_ci uses the docker image's distro +services: + - docker +language: cpp +cache: ccache +compiler: gcc + +notifications: + email: true env: global: - - SCRIPT=.moveit_ci/travis.sh - - ROS_DISTRO=noetic - - ROS_REPO=ros-testing + - MOVEIT_CI_TRAVIS_TIMEOUT=85 # Travis grants us 90 min, but we add a safety margin of 5 min + - ROS_DISTRO=foxy + - ROS_REPO=ros + - UPSTREAM_WORKSPACE="moveit2_tutorials.repos, moveit2.repos" - CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls" - WARNINGS_OK=false - - UPSTREAM_WORKSPACE="https://github.com/ros-planning/moveit_visual_tools - https://github.com/ros-planning/panda_moveit_config" - matrix: - - SCRIPT=htmlproofer.sh - - TEST="clang-format catkin_lint" - - TEST="clang-tidy-fix" - - DOCKER_IMAGE=moveit/moveit:master-source ROS_REPO= + +jobs: + fast_finish: true + include: + - name: "[Foxy] - htmlproofer" + env: SCRIPT=htmlproofer.sh + - name: "[Foxy] - clang-format, ament_lint" + env: TEST="clang-format ament_lint" + - name: "[Foxy] - gcc (build,test)" + env: ROS_DISTRO=foxy before_script: - - git clone -q --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci + - git clone -q -b ros2 --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci script: - ./$SCRIPT + - .moveit_ci/travis.sh deploy: # Deploy to gh-pages branch @@ -40,4 +47,4 @@ deploy: on: branch: main condition: $SCRIPT = htmlproofer.sh - fqdn: moveit2_tutorials.picknik.ai \ No newline at end of file + fqdn: moveit2_tutorials.picknik.ai diff --git a/CMakeLists.txt b/CMakeLists.txt index 0d1727236a..d678bc9f0d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,75 +1,82 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 3.10.2) project(moveit2_tutorials) -set(CMAKE_CXX_STANDARD 14) -set(CMAKE_CXX_EXTENSIONS OFF) - -find_package(catkin REQUIRED - COMPONENTS - interactive_markers - moveit_core - moveit_ros_planning - moveit_ros_planning_interface - moveit_ros_perception - rviz_visual_tools - moveit_visual_tools - pluginlib - geometric_shapes - pcl_ros - pcl_conversions - rosbag - tf2_ros - tf2_eigen - tf2_geometry_msgs -) +# Common cmake code applied to all moveit packages +find_package(moveit_common REQUIRED) +moveit_package() find_package(Eigen3 REQUIRED) find_package(Boost REQUIRED system filesystem date_time thread) +find_package(ament_cmake REQUIRED) +find_package(moveit_core REQUIRED) +find_package(moveit_ros_planning REQUIRED) +find_package(moveit_ros_planning_interface REQUIRED) +find_package(moveit_ros_perception REQUIRED) +find_package(interactive_markers REQUIRED) +find_package(rviz_visual_tools REQUIRED) +#find_package(moveit_visual_tools REQUIRED) +find_package(geometric_shapes REQUIRED) +#find_package(pcl_ros REQUIRED) +#find_package(pcl_conversions REQUIRED) +#find_package(rosbag REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(pluginlib REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(tf2_eigen REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) set(THIS_PACKAGE_INCLUDE_DIRS doc/interactivity/include ) -catkin_package( - LIBRARIES - INCLUDE_DIRS - CATKIN_DEPENDS - moveit_core - moveit_visual_tools - moveit_ros_planning_interface - interactive_markers - tf2_geometry_msgs - DEPENDS - EIGEN3 +set(THIS_PACKAGE_INCLUDE_DEPENDS + ament_cmake + rclcpp + rclcpp_action + tf2_geometry_msgs + tf2_ros + moveit_core + rviz_visual_tools + # moveit_visual_tools + moveit_ros_planning_interface + interactive_markers + tf2_geometry_msgs + moveit_ros_planning + pluginlib + Eigen3 + Boost ) -########### -## Build ## -########### - include_directories(${THIS_PACKAGE_INCLUDE_DIRS}) -include_directories(SYSTEM ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIRS}) -add_subdirectory(doc/controller_configuration) -add_subdirectory(doc/hand_eye_calibration) -add_subdirectory(doc/interactivity) -add_subdirectory(doc/kinematics) -add_subdirectory(doc/motion_planning_api) -add_subdirectory(doc/motion_planning_pipeline) -add_subdirectory(doc/move_group_interface) -add_subdirectory(doc/move_group_python_interface) -add_subdirectory(doc/perception_pipeline) -add_subdirectory(doc/pick_place) -add_subdirectory(doc/planning) -add_subdirectory(doc/planning_scene) -add_subdirectory(doc/planning_scene_ros_api) -add_subdirectory(doc/robot_model_and_robot_state) -add_subdirectory(doc/state_display) -add_subdirectory(doc/subframes) -add_subdirectory(doc/tests) -add_subdirectory(doc/trajopt_planner) -add_subdirectory(doc/creating_moveit_plugins/lerp_motion_planner) -add_subdirectory(doc/moveit_cpp) -add_subdirectory(doc/collision_environments) -add_subdirectory(doc/visualizing_collisions) -add_subdirectory(doc/bullet_collision_checker) +# add_subdirectory(doc/controller_configuration) +# add_subdirectory(doc/interactivity) +# add_subdirectory(doc/kinematics) +# add_subdirectory(doc/motion_planning_api) +# add_subdirectory(doc/motion_planning_pipeline) +# add_subdirectory(doc/move_group_interface) +# add_subdirectory(doc/move_group_python_interface) +# add_subdirectory(doc/perception_pipeline) +# add_subdirectory(doc/pick_place) +# add_subdirectory(doc/planning) +# add_subdirectory(doc/planning_scene) +# add_subdirectory(doc/planning_scene_ros_api) +# add_subdirectory(doc/robot_model_and_robot_state) +# add_subdirectory(doc/state_display) +# add_subdirectory(doc/subframes) +# add_subdirectory(doc/tests) +# add_subdirectory(doc/trajopt_planner) +# add_subdirectory(doc/creating_moveit_plugins/lerp_motion_planner) +# add_subdirectory(doc/moveit_cpp) +# add_subdirectory(doc/collision_environments) +# add_subdirectory(doc/visualizing_collisions) +# add_subdirectory(doc/bullet_collision_checker) + +ament_export_dependencies( + ${THIS_PACKAGE_INCLUDE_DEPENDS} +) + +ament_export_include_directories(include) + +ament_package() diff --git a/README.md b/README.md index 43fc6d7a12..cd94b2d0ef 100644 --- a/README.md +++ b/README.md @@ -2,7 +2,7 @@ **NOTE: This repository is still being set up and is not ready for contributions. The content on this readme and most of the repo is still legacy content from the [MoveIt 1 tutorials](https://ros-planning.github.io/moveit_tutorials/).** -This is the primary documentation for the MoveIt project. We strongly encourage you to help improve MoveIt's documentation. Please consider reading the guidelines below for writing the best documentation and tutorials. However, if you are uncomfortable with any of the approaches, simply adding documentation text to your pull requests is better than nothing. +This is the primary documentation for the MoveIt2 project. We strongly encourage you to help improve MoveIt's documentation. Please consider reading the guidelines below for writing the best documentation and tutorials. However, if you are uncomfortable with any of the approaches, simply adding documentation text to your pull requests is better than nothing. These tutorials use the [reStructuredText](http://www.sphinx-doc.org/en/stable/rest.html) format commonly used in the Sphinx "Python Documentation Generator". This unfortunately differs from the common Markdown format, but its advantage is that it supports embedding code directly from source files for inline code tutorials. @@ -26,12 +26,28 @@ Below are some links to help with the ports. ## Versions -- ``indigo-devel`` usage is discouraged -- ``kinetic-devel`` stable -- ``melodic-devel`` stable -- ``master`` latest, changes should target this branch +- ``main`` latest, changes should target this branch -## Build Locally +## MoveIt2 Tutorials Source Build + +Follow the [MoveIt 2 Source Build](https://moveit.ros.org/install-moveit2/source/) instructions to setup a colcon workspace with moveit2 from source. + +Cd into your moveit2 colcon workspace: + + cd $COLCON_WS/src + +Download Moveit2_tutorials Source Code + + wget https://raw.githubusercontent.com/ros-planning/moveit2_tutorials/main/moveit2_tutorials.repos + vcs import < moveit2_tutorials.repos + rosdep install -r --from-paths . --ignore-src --rosdistro foxy -y + +Configure and build the workspace: + + cd $COLCON_WS + colcon build --event-handlers desktop_notification- status- --cmake-args -DCMAKE_BUILD_TYPE=Release + +## Build HTML Pages Locally If you want to test the tutorials by generating the html pages locally on your machine, you will first need to install the `rosdoc_lite` package, and then you can use the ``build_locally`` script. Run in the root of the moveit_tutorials package: diff --git a/doc/controller_configuration/CMakeLists.txt b/doc/controller_configuration/CMakeLists.txt index 0b2788895c..527e2e18b1 100644 --- a/doc/controller_configuration/CMakeLists.txt +++ b/doc/controller_configuration/CMakeLists.txt @@ -1,6 +1,9 @@ -add_library(controller_manager_example src/moveit_controller_manager_example.cpp) -target_link_libraries(controller_manager_example ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS controller_manager_example DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +add_library(controller_manager_example + src/moveit_controller_manager_example.cpp) +target_link_libraries(controller_manager_example + ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +install(TARGETS controller_manager_example DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) # Need to use non-standard install location to find plugin description both in devel and install space install(FILES moveit_controller_manager_example_plugin_description.xml diff --git a/doc/hand_eye_calibration/CMakeLists.txt b/doc/hand_eye_calibration/CMakeLists.txt deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/doc/motion_planning_api/CMakeLists.txt b/doc/motion_planning_api/CMakeLists.txt index 71e60c7eb3..2a87b0f509 100644 --- a/doc/motion_planning_api/CMakeLists.txt +++ b/doc/motion_planning_api/CMakeLists.txt @@ -1,5 +1,8 @@ -add_executable(motion_planning_api_tutorial src/motion_planning_api_tutorial.cpp) -target_link_libraries(motion_planning_api_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS motion_planning_api_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +add_executable(motion_planning_api_tutorial + src/motion_planning_api_tutorial.cpp) +target_link_libraries(motion_planning_api_tutorial + ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +install(TARGETS motion_planning_api_tutorial DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/doc/motion_planning_pipeline/CMakeLists.txt b/doc/motion_planning_pipeline/CMakeLists.txt index 1f121cfb03..8dc42ca3e3 100644 --- a/doc/motion_planning_pipeline/CMakeLists.txt +++ b/doc/motion_planning_pipeline/CMakeLists.txt @@ -1,5 +1,8 @@ -add_executable(motion_planning_pipeline_tutorial src/motion_planning_pipeline_tutorial.cpp) -target_link_libraries(motion_planning_pipeline_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS motion_planning_pipeline_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +add_executable(motion_planning_pipeline_tutorial + src/motion_planning_pipeline_tutorial.cpp) +target_link_libraries(motion_planning_pipeline_tutorial + ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +install(TARGETS motion_planning_pipeline_tutorial DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/doc/move_group_interface/CMakeLists.txt b/doc/move_group_interface/CMakeLists.txt index 3c80c09c88..03fcfd4976 100644 --- a/doc/move_group_interface/CMakeLists.txt +++ b/doc/move_group_interface/CMakeLists.txt @@ -1,5 +1,8 @@ -add_executable(move_group_interface_tutorial src/move_group_interface_tutorial.cpp) -target_link_libraries(move_group_interface_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS move_group_interface_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +add_executable(move_group_interface_tutorial + src/move_group_interface_tutorial.cpp) +target_link_libraries(move_group_interface_tutorial + ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +install(TARGETS move_group_interface_tutorial DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/doc/planning/CMakeLists.txt b/doc/planning/CMakeLists.txt deleted file mode 100644 index 8b13789179..0000000000 --- a/doc/planning/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ - diff --git a/doc/planning_scene_ros_api/CMakeLists.txt b/doc/planning_scene_ros_api/CMakeLists.txt index 45e1433fe6..1c6c285ac9 100644 --- a/doc/planning_scene_ros_api/CMakeLists.txt +++ b/doc/planning_scene_ros_api/CMakeLists.txt @@ -1,5 +1,8 @@ -add_executable(planning_scene_ros_api_tutorial src/planning_scene_ros_api_tutorial.cpp) -target_link_libraries(planning_scene_ros_api_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS planning_scene_ros_api_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +add_executable(planning_scene_ros_api_tutorial + src/planning_scene_ros_api_tutorial.cpp) +target_link_libraries(planning_scene_ros_api_tutorial + ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +install(TARGETS planning_scene_ros_api_tutorial DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/doc/robot_model_and_robot_state/CMakeLists.txt b/doc/robot_model_and_robot_state/CMakeLists.txt index 90a7257a52..a76e7f3417 100644 --- a/doc/robot_model_and_robot_state/CMakeLists.txt +++ b/doc/robot_model_and_robot_state/CMakeLists.txt @@ -1,5 +1,8 @@ -add_executable(robot_model_and_robot_state_tutorial src/robot_model_and_robot_state_tutorial.cpp) -target_link_libraries(robot_model_and_robot_state_tutorial ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +add_executable(robot_model_and_robot_state_tutorial + src/robot_model_and_robot_state_tutorial.cpp) +target_link_libraries(robot_model_and_robot_state_tutorial + ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS robot_model_and_robot_state_tutorial DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +install(TARGETS robot_model_and_robot_state_tutorial DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/moveit2.repos b/moveit2.repos new file mode 100644 index 0000000000..3c6989cff4 --- /dev/null +++ b/moveit2.repos @@ -0,0 +1,47 @@ +repositories: + moveit2: + type: git + url: https://github.com/ros-planning/moveit2 + version: main + moveit_msgs: + type: git + url: https://github.com/ros-planning/moveit_msgs + version: ros2 + moveit_resources: + type: git + url: https://github.com/ros-planning/moveit_resources + version: ros2 + geometric_shapes: + type: git + url: https://github.com/ros-planning/geometric_shapes + version: ros2 + srdfdom: + type: git + url: https://github.com/ros-planning/srdfdom + version: ros2 + +# TODO(#283): Switch to master after fixing breaking changes in ros2_control + ros2_control: + type: git + url: https://github.com/ros-controls/ros2_control + version: 2c3aad1cb8ad4d23925bceeb5c26e22d6cf859ef + ros2_controllers: + type: git + url: https://github.com/ros-controls/ros2_controllers + version: 8587e079490acdd0fabeb2742a3bec3bf551bbc5 + +# TODO(JafarAbdi): Switch to upstream once PR https://github.com/tork-a/fake_joint/pull/7 is merged + fake_joint: + type: git + url: https://github.com/JafarAbdi/fake_joint + version: foxy + + warehouse_ros: + type: git + url: https://github.com/ros-planning/warehouse_ros + version: ros2 + + warehouse_ros_mongo: + type: git + url: https://github.com/ros-planning/warehouse_ros_mongo + version: ros2 diff --git a/moveit2_tutorials.repos b/moveit2_tutorials.repos new file mode 100644 index 0000000000..bda2665334 --- /dev/null +++ b/moveit2_tutorials.repos @@ -0,0 +1,9 @@ +repositories: + moveit2_tutorials: + type: git + url: https://github.com/ros-planning/moveit2_tutorials.git + version: main + rviz_visual_tools: + type: git + url: https://github.com/PickNikRobotics/rviz_visual_tools.git + version: foxy-devel diff --git a/package.xml b/package.xml index b663f4f2d2..8675bddfea 100644 --- a/package.xml +++ b/package.xml @@ -2,7 +2,7 @@ moveit2_tutorials 0.1.0 - The moveit_tutorials package + The moveit2_tutorials package BSD Sachin Chitta @@ -16,7 +16,8 @@ https://github.com/ros-planning/moveit2_tutorials https://github.com/ros-planning/moveit2_tutorials/issues - catkin + ament_cmake + moveit_common pluginlib eigen @@ -26,48 +27,53 @@ moveit_ros_perception interactive_markers geometric_shapes - moveit_visual_tools + rviz_visual_tools - pcl_ros - pcl_conversions - rosbag + + + tf2_ros tf2_eigen tf2_geometry_msgs - panda_moveit_config - franka_description + + pluginlib moveit_core - moveit_commander + moveit_fake_controller_manager moveit_ros_planning_interface moveit_ros_perception interactive_markers - moveit_visual_tools + rviz_visual_tools joint_state_publisher robot_state_publisher joy - pcl_ros - pcl_conversions - rosbag - rviz + + + + rviz2 tf2_ros tf2_eigen tf2_geometry_msgs xacro moveit_resources_panda_moveit_config - rosunit + ament_cmake_gtest + ament_cmake -