From 549a2ee2dd7e9f81e6b1f129353886504bcbc432 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 10 Jan 2025 01:16:13 +0100 Subject: [PATCH] Use ! in place of not keyword for Pilz and CHOMP planners (#3217) * pilz_industrial_motion_planner: Use ! in place of not keyword for consistency * Use ! in place of not keyword for chomp_planner.cpp --------- Co-authored-by: JafarAbdi --- .../chomp/chomp_motion_planner/src/chomp_planner.cpp | 2 +- .../include/joint_limits_copy/joint_limits_rosparam.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp index 09a7251d67..41186e9db4 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp @@ -281,7 +281,7 @@ void ChompPlanner::solve(const planning_scene::PlanningSceneConstPtr& planning_s res.processing_time[0] = std::chrono::duration(std::chrono::system_clock::now() - start_time).count(); // report planning failure if path has collisions - if (not optimizer->isCollisionFree()) + if (!optimizer->isCollisionFree()) { RCLCPP_ERROR(getLogger(), "Motion plan is invalid."); res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN; diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp index 89bd99f1da..b135d1c3d3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp @@ -32,7 +32,7 @@ namespace template void declareParameterTemplate(const rclcpp::Node::SharedPtr& node, const std::string& name, T default_value) { - if (not node->has_parameter(name)) + if (!node->has_parameter(name)) { node->declare_parameter(name, default_value); }