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 dbfcb28a1e..598a1fc8ab 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_planner.cpp @@ -256,7 +256,7 @@ bool ChompPlanner::solve(const planning_scene::PlanningSceneConstPtr& planning_s res.processing_time_[0] = (ros::WallTime::now() - start_time).toSec(); // report planning failure if path has collisions - if (not optimizer->isCollisionFree()) + if (!optimizer->isCollisionFree()) { ROS_ERROR_STREAM_NAMED("chomp_planner", "Motion plan is invalid."); res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN; diff --git a/moveit_planners/trajopt/src/trajopt_interface.cpp b/moveit_planners/trajopt/src/trajopt_interface.cpp index 30b3c9ef1a..a449645989 100644 --- a/moveit_planners/trajopt/src/trajopt_interface.cpp +++ b/moveit_planners/trajopt/src/trajopt_interface.cpp @@ -111,7 +111,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni return false; } - if (not joint_model_group->satisfiesPositionBounds(start_joint_values.data())) + if (!joint_model_group->satisfiesPositionBounds(start_joint_values.data())) { ROS_ERROR_STREAM_NAMED(name_, "Start state violates joint limits"); res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE; @@ -326,7 +326,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni constraint.tolerance_above); constraints_are_ok = constraints_are_ok and joint_cnt.configure(constraint); constraints_are_ok = constraints_are_ok and joint_cnt.decide(last_state).satisfied; - if (not constraints_are_ok) + if (!constraints_are_ok) { ROS_ERROR_STREAM_NAMED("trajopt_planner", "Goal constraints are violated: " << constraint.joint_name); res.error_code.val = moveit_msgs::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;