Skip to content

Commit

Permalink
Compilation fixes for Jammy and bring back Rolling CI (moveit#1095)
Browse files Browse the repository at this point in the history
* Use jammy dockers and clang-format-12
* Fix unused depend, and move to python3-lxml
* add ompl to repos, fix versions and ogre
* Remove ogre keys
* Fix boolean node operator
* Stop building dockers on branch and fix servo null pointer
* update pre-commit to clang-format-12 and pre-commit fixes
* clang-format workaround and more pre-commit fixes
  • Loading branch information
Vatan Aksoy Tezer committed Mar 3, 2022
1 parent 92c3e84 commit 419db3b
Show file tree
Hide file tree
Showing 21 changed files with 40 additions and 29 deletions.
4 changes: 2 additions & 2 deletions .docker/ci/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# ROS base image augmented with all MoveIt dependencies to use for CI

ARG ROS_DISTRO=rolling
FROM ros:${ROS_DISTRO}-ros-base-focal
FROM ros:${ROS_DISTRO}-ros-base
MAINTAINER Robert Haschke rhaschke@techfak.uni-bielefeld.de

ENV TERM xterm
Expand All @@ -25,7 +25,7 @@ RUN \
# Some basic requirements
wget git sudo curl \
# Preferred build tools
clang clang-format-10 clang-tidy clang-tools \
clang clang-format-12 clang-tidy clang-tools \
ccache && \
#
# Fetch all dependencies from moveit2.repos
Expand Down
2 changes: 1 addition & 1 deletion .docker/release/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# Full debian-based install of MoveIt using apt-get

ARG ROS_DISTRO=rolling
FROM ros:${ROS_DISTRO}-ros-base-focal
FROM ros:${ROS_DISTRO}-ros-base
MAINTAINER Robert Haschke rhaschke@techfak.uni-bielefeld.de

# Commands are combined in single RUN statement with "apt/lists" folder removal to reduce image size
Expand Down
8 changes: 4 additions & 4 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@ jobs:
fail-fast: false
matrix:
env:
- IMAGE: galactic-ci
- IMAGE: rolling-ci
CCOV: true
ROS_DISTRO: galactic
- IMAGE: galactic-ci-testing
ROS_DISTRO: rolling
- IMAGE: rolling-ci-testing
IKFAST_TEST: true
ROS_DISTRO: galactic
ROS_DISTRO: rolling
CLANG_TIDY: pedantic
env:
CXXFLAGS: "-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-deprecated-copy"
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/format.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@ jobs:
steps:
- uses: actions/checkout@v2
- uses: actions/setup-python@v2
- name: Install clang-format-10
run: sudo apt-get install clang-format-10
- name: Install clang-format-12
run: sudo apt-get install clang-format-12
- uses: pre-commit/action@v2.0.3
id: precommit
- name: Upload pre-commit changes
Expand Down
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ repos:
- id: clang-format
name: clang-format
description: Format files with ClangFormat.
entry: clang-format-10
entry: clang-format-12
language: system
files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$
args: ['-fallback-style=none', '-i']
Expand Down
6 changes: 5 additions & 1 deletion moveit2.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ repositories:
geometric_shapes:
type: git
url: https://github.com/ros-planning/geometric_shapes
version: 2.1.2
version: ros2
moveit_msgs:
type: git
url: https://github.com/ros-planning/moveit_msgs
Expand All @@ -19,3 +19,7 @@ repositories:
type: git
url: https://github.com/ros-controls/ros2_control.git
version: 2.1.0
ompl:
type: git
url: https://github.com/ompl/ompl.git
version: main
2 changes: 1 addition & 1 deletion moveit_kinematics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

<!-- some requirements of ikfast scripts -->
<exec_depend>urdfdom</exec_depend> <!-- provides check_urdf -->
<exec_depend>python-lxml</exec_depend>
<exec_depend>python3-lxml</exec_depend>

<test_depend>moveit_ros_planning</test_depend>
<test_depend>moveit_resources_fanuc_description</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class PlanningContextTest : public ::testing::Test
planning_scene::PlanningScenePtr scene(new planning_scene::PlanningScene(robot_model_));
moveit::core::RobotState current_state(robot_model_);
current_state.setToDefaultValues();
current_state.setJointGroupPositions(planning_group_, { 0, 1.57, 1.57, 0, 0.2, 0 });
current_state.setJointGroupPositions(planning_group_, std::vector<double>{ 0, 1.57, 1.57, 0, 0.2, 0 });
scene->setCurrentState(current_state);
planning_context_->setPlanningScene(scene); // TODO Check what happens if this is missing
}
Expand All @@ -148,8 +148,9 @@ class PlanningContextTest : public ::testing::Test
// state state in joint space, used as initial positions, since IK does not
// work at zero positions
rstate.setJointGroupPositions(this->planning_group_,
{ 4.430233957464225e-12, 0.007881892504574495, -1.8157263253868452,
1.1801525390026025e-11, 1.8236082178909834, 8.591793942969161e-12 });
std::vector<double>{ 4.430233957464225e-12, 0.007881892504574495, -1.8157263253868452,
1.1801525390026025e-11, 1.8236082178909834,
8.591793942969161e-12 });
Eigen::Isometry3d start_pose(Eigen::Isometry3d::Identity());
start_pose.translation() = Eigen::Vector3d(0.3, 0, 0.65);
rstate.setFromIK(this->robot_model_->getJointModelGroup(this->planning_group_), start_pose);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ class TrajectoryGeneratorCommonTest : public ::testing::Test
req_.max_acceleration_scaling_factor = 1.0;
moveit::core::RobotState rstate(robot_model_);
rstate.setToDefaultValues();
rstate.setJointGroupPositions(planning_group_, { 0, M_PI / 2, 0, M_PI / 2, 0, 0 });
rstate.setJointGroupPositions(planning_group_, std::vector<double>{ 0, M_PI / 2, 0, M_PI / 2, 0, 0 });
rstate.setVariableVelocities(std::vector<double>(rstate.getVariableCount(), 0.0));
moveit::core::robotStateToRobotStateMsg(rstate, req_.start_state, false);
moveit_msgs::msg::Constraints goal_constraint;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -147,9 +147,9 @@ bool executeAttachObject(const ManipulationPlanSharedDataConstPtr& shared_plan_d
ok = ps->processAttachedCollisionObjectMsg(msg);
}
motion_plan->planning_scene_monitor_->triggerSceneUpdateEvent(
(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType)(
planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY +
planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE));
(planning_scene_monitor::PlanningSceneMonitor::
SceneUpdateType)(planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY +
planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE));
return ok;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <rcl_interfaces/msg/integer_range.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <rcl_interfaces/msg/parameter_type.hpp>
#include <limits>
#include <string>

namespace moveit_servo
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/test/servo_launch_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ class ServoFixture : public ::testing::Test
// Otherwise the Servo is still running when another test starts...
if (!client_servo_stop_)
{
client_servo_stop_->async_send_request(std::make_shared<std_srvs::srv::Trigger::Request>());
stop();
}
executor_->cancel();
if (executor_thread_.joinable())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -648,7 +648,7 @@ class LockedPlanningSceneRO
return planning_scene_monitor_ && planning_scene_monitor_->getPlanningScene();
}

operator const planning_scene::PlanningSceneConstPtr &() const
operator const planning_scene::PlanningSceneConstPtr&() const
{
return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
}
Expand Down Expand Up @@ -729,7 +729,7 @@ class LockedPlanningSceneRW : public LockedPlanningSceneRO
{
}

operator const planning_scene::PlanningScenePtr &()
operator const planning_scene::PlanningScenePtr&()
{
return planning_scene_monitor_->getPlanningScene();
}
Expand Down
1 change: 0 additions & 1 deletion moveit_ros/visualization/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@

<build_depend>class_loader</build_depend>
<build_depend>eigen</build_depend>
<build_depend>libogre-dev</build_depend>
<build_depend>libqt5-opengl-dev</build_depend>
<build_depend>qtbase5-dev</build_depend>

Expand Down
3 changes: 2 additions & 1 deletion moveit_ros/warehouse/warehouse/src/broadcast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ int main(int argc, char** argv)
// time to wait in between publishing messages
double delay = 0.001;

// clang-format off
boost::program_options::options_description desc;
desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
"Host for the "
Expand All @@ -80,7 +81,7 @@ int main(int argc, char** argv)
"state", boost::program_options::value<std::string>(),
"Name of the robot state to publish.")("delay", boost::program_options::value<double>()->default_value(delay),
"Time to wait in between publishing messages (s)");

// clang-format on
boost::program_options::variables_map vm;
boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
boost::program_options::notify(vm);
Expand Down
2 changes: 2 additions & 0 deletions moveit_ros/warehouse/warehouse/src/import_from_text.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,12 +216,14 @@ int main(int argc, char** argv)
node_options.automatically_declare_parameters_from_overrides(true);
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("import_from_text_to_warehouse", node_options);

// clang-format off
boost::program_options::options_description desc;
desc.add_options()("help", "Show help message")("queries", boost::program_options::value<std::string>(),
"Name of file containing motion planning queries.")(
"scene", boost::program_options::value<std::string>(), "Name of file containing motion planning scene.")(
"host", boost::program_options::value<std::string>(),
"Host for the DB.")("port", boost::program_options::value<std::size_t>(), "Port for the DB.");
// clang-format on

boost::program_options::variables_map vm;
boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
Expand Down
1 change: 0 additions & 1 deletion moveit_setup_assistant/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>moveit_common</build_depend>
<build_depend>libogre-dev</build_depend>
<build_depend>ompl</build_depend>

<depend>ament_index_cpp</depend>
Expand Down
2 changes: 2 additions & 0 deletions moveit_setup_assistant/src/collisions_updater.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,7 @@ int main(int argc, char* argv[])

uint32_t never_trials = 0;

// clang-format off
po::options_description desc("Allowed options");
desc.add_options()("help", "show help")("config-pkg", po::value(&config_pkg_path), "path to MoveIt config package")(
"urdf", po::value(&urdf_path), "path to URDF ( or xacro)")("srdf", po::value(&srdf_path),
Expand All @@ -141,6 +142,7 @@ int main(int argc, char* argv[])
"number of trials for searching never colliding pairs")(
"min-collision-fraction", po::value(&min_collision_fraction),
"fraction of small sample size to determine links that are always colliding");
// clang-format on

po::positional_options_description pos_desc;
pos_desc.add("xacro-args", -1);
Expand Down
2 changes: 2 additions & 0 deletions moveit_setup_assistant/src/setup_assistant_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,12 @@ int main(int argc, char** argv)
namespace po = boost::program_options;

// Declare the supported options
// clang-format off
po::options_description desc("Allowed options");
desc.add_options()("help,h", "Show help message")("debug,g", "Run in debug/test mode")(
"urdf_path,u", po::value<std::string>(), "Optional, path to URDF file in ROS package")(
"config_pkg,c", po::value<std::string>(), "Optional, pass in existing config package to load");
// clang-format on

// Process options
po::variables_map vm;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ const boost::unordered_map<DisabledReason, std::string> REASONS_TO_STRING = boos
DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled");

const boost::unordered_map<std::string, DisabledReason> REASONS_FROM_STRING =
boost::assign::map_list_of("Never", NEVER)("Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)(
"User", USER)("Not Disabled", NOT_DISABLED);
boost::assign::map_list_of("Never", NEVER)("Default", DEFAULT)(
"Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED);

// Used for logging
static const rclcpp::Logger LOGGER = rclcpp::get_logger("collision_updater");
Expand Down
4 changes: 2 additions & 2 deletions moveit_setup_assistant/src/tools/moveit_config_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1207,7 +1207,7 @@ class SortableDisabledCollision
: dc_(dc), key_(dc.link1_ < dc.link2_ ? (dc.link1_ + "|" + dc.link2_) : (dc.link2_ + "|" + dc.link1_))
{
}
operator const srdf::Model::DisabledCollision &() const
operator const srdf::Model::DisabledCollision&() const
{
return dc_;
}
Expand Down Expand Up @@ -1287,7 +1287,7 @@ template <typename T>
bool parse(const YAML::Node& node, const std::string& key, T& storage, const T& default_value = T())
{
const YAML::Node& n = node[key];
bool valid = n;
bool valid = n.IsDefined();
storage = valid ? n.as<T>() : default_value;
return valid;
}
Expand Down

0 comments on commit 419db3b

Please sign in to comment.