diff --git a/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp index 503a1a3c89..ca7faf118e 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/path_circle_generator.cpp @@ -65,8 +65,10 @@ std::unique_ptr PathCircleGenerator::circleFromCenter(const KDL::Fram } catch (KDL::Error_MotionPlanning&) { - delete rot_interpo; // in case we could not construct the Path object, avoid - // a memory leak +#if KDL_VERSION < ((1 << 16) | (4 << 8) | 1) // older than 1.4.1 ? + delete rot_interpo; // in case we could not construct the Path object, + // avoid a memory leak +#endif KDL::epsilon = old_kdl_epsilon; throw; // and pass the exception on to the caller } @@ -132,9 +134,11 @@ std::unique_ptr PathCircleGenerator::circleFromInterim(const KDL::Fra // above, // we keep these lines to be safe { - delete rot_interpo; // in case we could not construct the Path object, avoid - // a memory leak - throw; // and pass the exception on to the caller +#if KDL_VERSION < ((1 << 16) | (4 << 8) | 1) // older than 1.4.1 ? + delete rot_interpo; // in case we could not construct the Path object, + // avoid a memory leak +#endif + throw; // and pass the exception on to the caller // LCOV_EXCL_STOP } } diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_planning.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_planning.cpp index f275988fdb..22972abae7 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_planning.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_planning.cpp @@ -219,7 +219,7 @@ TEST_F(IntegrationTestCommandPlanning, PtpJointCart) Eigen::Isometry3d exp_iso3d_pose; tf2::fromMsg(expected_pose, exp_iso3d_pose); - EXPECT_TRUE(Eigen::Quaterniond(tf.rotation()).isApprox(Eigen::Quaterniond(exp_iso3d_pose.rotation()), EPSILON)); + EXPECT_TRUE(Eigen::Quaterniond(tf.rotation()).isApprox(Eigen::Quaterniond(exp_iso3d_pose.rotation()), 2 * EPSILON)); } /**