Skip to content

Commit

Permalink
Simplify formatting code with https://github.com/fmtlib (moveit#499)
Browse files Browse the repository at this point in the history
* Simplify formatting code with https://github.com/fmtlib
* Update to clang-format-12
  • Loading branch information
rhaschke authored May 25, 2024
1 parent a0c0064 commit 7666f73
Show file tree
Hide file tree
Showing 23 changed files with 170 additions and 184 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/format.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ jobs:
- uses: actions/checkout@v4
with:
submodules: recursive
- 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: rhaschke/[email protected]
with:
distro: noetic
Expand Down
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,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
3 changes: 2 additions & 1 deletion capabilities/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
cmake_minimum_required(VERSION 3.1.3)
project(moveit_task_constructor_capabilities)

find_package(fmt REQUIRED)
find_package(catkin REQUIRED COMPONENTS
actionlib
moveit_core
Expand Down Expand Up @@ -32,7 +33,7 @@ add_library(${PROJECT_NAME}
)
add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS})
target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${catkin_INCLUDE_DIRS})
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} fmt::fmt)

install(TARGETS ${PROJECT_NAME}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
1 change: 1 addition & 0 deletions capabilities/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>fmt</depend>
<depend>moveit_core</depend>
<depend>moveit_ros_move_group</depend>
<depend>actionlib</depend>
Expand Down
6 changes: 4 additions & 2 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <moveit/robot_state/conversions.h>
#include <moveit/utils/message_checks.h>
#include <moveit/utils/moveit_error_code.h>
#include <fmt/format.h>

namespace {

Expand Down Expand Up @@ -152,8 +153,9 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
if (!joint_names.empty()) {
group = findJointModelGroup(*model, joint_names);
if (!group) {
ROS_ERROR_STREAM_NAMED("ExecuteTaskSolution", "Could not find JointModelGroup that actuates {"
<< boost::algorithm::join(joint_names, ", ") << "}");
ROS_ERROR_STREAM_NAMED(
"ExecuteTaskSolution",
fmt::format("Could not find JointModelGroup that actuates {{{}}}", fmt::join(joint_names, ", ")));
return false;
}
ROS_DEBUG_NAMED("ExecuteTaskSolution", "Using JointModelGroup '%s' for execution",
Expand Down
1 change: 1 addition & 0 deletions core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 3.1.3)
project(moveit_task_constructor_core)

find_package(Boost REQUIRED)
find_package(fmt REQUIRED)
find_package(catkin REQUIRED COMPONENTS
roslint
tf2_eigen
Expand Down
3 changes: 2 additions & 1 deletion core/include/moveit/task_constructor/stage_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <moveit/task_constructor/cost_queue.h>

#include <ros/console.h>
#include <fmt/core.h>

#include <ostream>
#include <chrono>
Expand Down Expand Up @@ -144,7 +145,7 @@ class StagePrivate
void newSolution(const SolutionBasePtr& solution);
bool storeFailures() const { return introspection_ != nullptr; }
void runCompute() {
ROS_DEBUG_STREAM_NAMED("Stage", "Computing stage '" << name() << "'");
ROS_DEBUG_STREAM_NAMED("Stage", fmt::format("Computing stage '{}'", name()));
auto compute_start_time = std::chrono::steady_clock::now();
try {
compute();
Expand Down
1 change: 1 addition & 0 deletions core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<build_depend>roslint</build_depend>
<exec_depend>roscpp</exec_depend>

<depend>fmt</depend>
<depend>tf2_eigen</depend>
<depend>geometry_msgs</depend>
<depend>moveit_core</depend>
Expand Down
2 changes: 1 addition & 1 deletion core/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ add_library(${PROJECT_NAME}
solvers/pipeline_planner.cpp
solvers/multi_planner.cpp
)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} fmt::fmt)
target_include_directories(${PROJECT_NAME}
PUBLIC $<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>
Expand Down
Loading

0 comments on commit 7666f73

Please sign in to comment.