Skip to content

Commit

Permalink
Cleanup rolling, add galactic CI, and fixups
Browse files Browse the repository at this point in the history
  • Loading branch information
Vatan Aksoy Tezer committed Jun 11, 2021
1 parent e783ecc commit 85e43b6
Show file tree
Hide file tree
Showing 8 changed files with 137 additions and 30 deletions.
74 changes: 74 additions & 0 deletions .github/workflows/build_and_test_galactic.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git).
# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst)

name: Build and Test (galactic)

on:
workflow_dispatch:
pull_request:
push:
branches:
- main

jobs:
industrial_ci:
strategy:
matrix:
env:
- ROS_DISTRO: galactic
ROS_REPO: main
- ROS_DISTRO: galactic
ROS_REPO: testing
env:
UPSTREAM_WORKSPACE: moveit2_galactic.repos
AFTER_SETUP_UPSTREAM_WORKSPACE: vcs pull $BASEDIR/upstream_ws/src
TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Release
CCACHE_DIR: ${{ github.workspace }}/.ccache
BASEDIR: ${{ github.workspace }}/.work
CACHE_PREFIX: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
CLANG_TIDY_BASE_REF: ${{ github.base_ref || github.ref }}

name: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- name: cache upstream_ws
uses: pat-s/[email protected]
with:
path: ${{ env.BASEDIR }}/upstream_ws
key: upstream_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('moveit2_galactic.repos') }}-${{ github.run_id }}
restore-keys: |
upstream_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('moveit2_galactic.repos') }}
# The target directory cache doesn't include the source directory because
# that comes from the checkout. See "prepare target_ws for cache" task below
- name: cache target_ws
uses: pat-s/[email protected]
with:
path: ${{ env.BASEDIR }}/target_ws
key: target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}-${{ github.run_id }}
restore-keys: |
target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}
- name: cache ccache
uses: pat-s/[email protected]
with:
path: ${{ env.CCACHE_DIR }}
key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }}
restore-keys: |
ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}
ccache-${{ env.CACHE_PREFIX }}
- name: industrial_ci
uses: 'ros-industrial/industrial_ci@master'
env: ${{ matrix.env }}
- name: upload test artifacts (on failure)
uses: actions/upload-artifact@v2
if: failure()
with:
name: test-results
path: ${{ env.BASEDIR }}/target_ws/**/test_results/**/*.xml
- name: prepare target_ws for cache
if: always()
run: |
du -sh ${{ env.BASEDIR }}/target_ws
sudo find ${{ env.BASEDIR }}/target_ws -wholename '*/test_results/*' -delete
sudo rm -rf ${{ env.BASEDIR }}/target_ws/src
du -sh ${{ env.BASEDIR }}/target_ws
2 changes: 0 additions & 2 deletions .github/workflows/build_and_test_rolling.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@ jobs:
ROS_REPO: main
- ROS_DISTRO: rolling
ROS_REPO: testing
# galactic is not yet supported by industrial_ci
# - ROS_DISTRO: galactic
env:
UPSTREAM_WORKSPACE: moveit2_rolling.repos
AFTER_SETUP_UPSTREAM_WORKSPACE: vcs pull $BASEDIR/upstream_ws/src
Expand Down
49 changes: 49 additions & 0 deletions moveit2_galactic.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
repositories:
control_msgs:
type: git
url: https://github.com/ros-controls/control_msgs
version: galactic-devel
control_toolbox:
type: git
url: https://github.com/ros-controls/control_toolbox
version: ros2-master
geometric_shapes:
type: git
url: https://github.com/ros-planning/geometric_shapes
version: ros2
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
object_recognition_msgs:
type: git
url: https://github.com/wg-perception/object_recognition_msgs
version: ros2
random_numbers:
type: git
url: https://github.com/ros-planning/random_numbers
version: ros2
ros2_control:
type: git
url: https://github.com/ros-controls/ros2_control
version: master
ros2_controllers:
type: git
url: https://github.com/ros-controls/ros2_controllers
version: master
srdfdom:
type: git
url: https://github.com/ros-planning/srdfdom
version: ros2
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
28 changes: 4 additions & 24 deletions moveit2_rolling.repos
Original file line number Diff line number Diff line change
@@ -1,4 +1,8 @@
repositories:
control_msgs:
type: git
url: https://github.com/ros-controls/control_msgs
version: galactic-devel
control_toolbox:
type: git
url: https://github.com/ros-controls/control_toolbox
Expand All @@ -15,30 +19,6 @@ repositories:
type: git
url: https://github.com/ros-planning/moveit_resources
version: ros2
object_recognition_msgs:
type: git
url: https://github.com/wg-perception/object_recognition_msgs
version: ros2
octomap:
type: git
url: https://github.com/octomap/octomap
version: devel
octomap_msgs:
type: git
url: https://github.com/OctoMap/octomap_msgs
version: ros2
ompl:
type: git
url: https://github.com/ompl/ompl
version: 1.5.0
random_numbers:
type: git
url: https://github.com/ros-planning/random_numbers
version: ros2
realtime_tools:
type: git
url: https://github.com/ros-controls/realtime_tools
version: foxy-devel
ros2_control:
type: git
url: https://github.com/ros-controls/ros2_control
Expand Down
1 change: 1 addition & 0 deletions moveit_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,7 @@ if(BUILD_TESTING)
set(ament_cmake_cppcheck_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
set(ament_cmake_uncrustify_FOUND TRUE)
set(ament_cmake_lint_cmake_FOUND TRUE)

# Run all lint tests in package.xml except those listed above
ament_lint_auto_find_test_dependencies()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <stdexcept>
#include <sstream>
#include <memory>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <moveit/warehouse/constraints_storage.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/move_group/capability_names.h>
Expand Down
3 changes: 2 additions & 1 deletion moveit_ros/planning_interface/moveit_cpp/src/moveit_cpp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@
#include <moveit/moveit_cpp/moveit_cpp.h>
#include <moveit/planning_scene_monitor/current_state_monitor.h>
#include <moveit/common_planning_interface_objects/common_objects.h>

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <geometry_msgs/msg/quaternion_stamped.h>
#include <tf2/utils.h>
#include <tf2_ros/transform_listener.h>
#include <rclcpp/rclcpp.hpp>
Expand Down
9 changes: 6 additions & 3 deletions moveit_ros/robot_interaction/src/robot_interaction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -572,10 +572,13 @@ void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable)
{
std::string topic_name = int_marker_move_topics_[i];
std::string marker_name = int_marker_names_[i];
int_marker_move_subscribers_.push_back(node_->create_subscription<geometry_msgs::msg::PointStamped>(
topic_name, 1, [this, marker_name](const geometry_msgs::msg::PoseStamped::ConstSharedPtr msg) {
std::function<void(const geometry_msgs::msg::PoseStamped::SharedPtr)> subscription_callback =
[this, marker_name](const geometry_msgs::msg::PoseStamped::SharedPtr msg) {
moveInteractiveMarker(marker_name, msg);
}));
};
auto subscription =
node_->create_subscription<geometry_msgs::msg::PoseStamped>(topic_name, 1, subscription_callback);
int_marker_move_subscribers_.push_back(subscription);
}
}
}
Expand Down

0 comments on commit 85e43b6

Please sign in to comment.