From 0a2906e8c21d7653066d1377067dc5e2691ee22d Mon Sep 17 00:00:00 2001 From: John Wason Date: Thu, 1 Aug 2024 14:54:04 -0400 Subject: [PATCH] Fix Mac OS clang compiler warnings (#496) --- .github/workflows/mac.yml | 6 +++-- .../src/poly/cartesian_waypoint_poly.cpp | 3 ++- .../simple/src/interpolation.cpp | 26 +++++++++---------- ...planner_fixed_size_assign_plan_profile.cpp | 2 +- .../trajopt/src/trajopt_motion_planner.cpp | 4 +-- tesseract_task_composer/CMakeLists.txt | 2 +- .../core/src/task_composer_keys.cpp | 2 -- .../src/ruckig_trajectory_smoothing.cpp | 7 ++--- .../time_optimal_trajectory_generation.cpp | 2 +- 9 files changed, 28 insertions(+), 26 deletions(-) diff --git a/.github/workflows/mac.yml b/.github/workflows/mac.yml index 34a7467e79..c37354106e 100644 --- a/.github/workflows/mac.yml +++ b/.github/workflows/mac.yml @@ -75,6 +75,7 @@ jobs: - name: colcon build working-directory: ws run: | + set -e export DYLD_LIBRARY_PATH=$DYLD_LIBRARY_PATH:$GITHUB_WORKSPACE/vcpkg/installed/${{ matrix.config.vcpkg_triplet }}/lib export CMAKE_PREFIX_PATH=$GITHUB_WORKSPACE/vcpkg/installed/${{ matrix.config.vcpkg_triplet }} @@ -91,11 +92,12 @@ jobs: -DOpenMP_C_INCLUDE_DIR=${{ matrix.config.homebrew_root }}/opt/libomp/include \ -DOpenMP_CXX_LIB_NAMES=libomp -DOpenMP_CXX_FLAGS="-Xpreprocessor -fopenmp" \ -DOpenMP_C_LIB_NAMES=libomp -DOpenMP_C_FLAGS="-Xpreprocessor -fopenmp" \ - -DOpenMP_libomp_LIBRARY=${{ matrix.config.homebrew_root }}/opt/libomp/lib/libomp.dylib - -Dtcmalloc_minimal_LIBRARY=${{ github.workspace }}/vcpkg/installed/x64-osx-dynamic-release/lib/libtcmalloc_minimal.dylib + -DOpenMP_libomp_LIBRARY=${{ matrix.config.homebrew_root }}/opt/libomp/lib/libomp.dylib \ + -Dtcmalloc_minimal_LIBRARY=${{ github.workspace }}/vcpkg/installed/${{ matrix.config.vcpkg_triplet }}/lib/libtcmalloc_minimal.dylib - name: colcon test working-directory: ws run: | + set -e export DYLD_LIBRARY_PATH=$DYLD_LIBRARY_PATH:$GITHUB_WORKSPACE/vcpkg/installed/${{ matrix.config.vcpkg_triplet }}/lib export CMAKE_PREFIX_PATH=$GITHUB_WORKSPACE/vcpkg/installed/${{ matrix.config.vcpkg_triplet }} diff --git a/tesseract_command_language/src/poly/cartesian_waypoint_poly.cpp b/tesseract_command_language/src/poly/cartesian_waypoint_poly.cpp index 0a14413e59..c10b822506 100644 --- a/tesseract_command_language/src/poly/cartesian_waypoint_poly.cpp +++ b/tesseract_command_language/src/poly/cartesian_waypoint_poly.cpp @@ -97,7 +97,8 @@ void tesseract_planning::CartesianWaypointPoly::print(const std::string& prefix) bool tesseract_planning::CartesianWaypointPoly::hasSeed() const { const auto& seed = getInterface().getSeed(); - return (seed.position.size() != 0 && !seed.joint_names.empty() && seed.position.size() == seed.joint_names.size()); + return (seed.position.size() != 0 && !seed.joint_names.empty() && + static_cast(seed.position.size()) == seed.joint_names.size()); } void tesseract_planning::CartesianWaypointPoly::clearSeed() { getInterface().setSeed(tesseract_common::JointState()); } diff --git a/tesseract_motion_planners/simple/src/interpolation.cpp b/tesseract_motion_planners/simple/src/interpolation.cpp index 7c2d4148e7..acb4e7cb69 100644 --- a/tesseract_motion_planners/simple/src/interpolation.cpp +++ b/tesseract_motion_planners/simple/src/interpolation.cpp @@ -222,7 +222,7 @@ std::vector interpolateJointJointWaypoint(const KinematicGr for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -286,7 +286,7 @@ std::vector interpolateJointCartWaypoint(const KinematicGro for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -349,7 +349,7 @@ std::vector interpolateCartJointWaypoint(const KinematicGro for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -451,7 +451,7 @@ std::vector interpolateCartCartWaypoint(const KinematicGrou for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -540,7 +540,7 @@ std::vector interpolateJointCartWaypoint(const KinematicGro for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -561,7 +561,7 @@ std::vector interpolateJointCartWaypoint(const KinematicGro for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -618,7 +618,7 @@ std::vector interpolateCartJointWaypoint(const KinematicGro for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -639,7 +639,7 @@ std::vector interpolateCartJointWaypoint(const KinematicGro for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -740,7 +740,7 @@ std::vector interpolateCartCartWaypoint(const KinematicGrou for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -786,7 +786,7 @@ std::vector interpolateJointJointWaypoint(const JointGroupI for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -839,7 +839,7 @@ std::vector interpolateJointCartWaypoint(const JointGroupIn for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -892,7 +892,7 @@ std::vector interpolateCartJointWaypoint(const JointGroupIn for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } @@ -948,7 +948,7 @@ std::vector interpolateCartCartWaypoint(const JointGroupIns for (auto& pose : poses) pose = base.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction); } diff --git a/tesseract_motion_planners/simple/src/profile/simple_planner_fixed_size_assign_plan_profile.cpp b/tesseract_motion_planners/simple/src/profile/simple_planner_fixed_size_assign_plan_profile.cpp index a434e7af25..4adc288996 100644 --- a/tesseract_motion_planners/simple/src/profile/simple_planner_fixed_size_assign_plan_profile.cpp +++ b/tesseract_motion_planners/simple/src/profile/simple_planner_fixed_size_assign_plan_profile.cpp @@ -117,7 +117,7 @@ SimplePlannerFixedSizeAssignPlanProfile::generate(const MoveInstructionPoly& pre for (auto& pose : poses) pose = info2.working_frame_transform.inverse() * pose; - assert(poses.size() == states.cols()); + assert(static_cast(poses.size()) == states.cols()); return getInterpolatedInstructions(poses, info2.manip->getJointNames(), states, info2.instruction); } diff --git a/tesseract_motion_planners/trajopt/src/trajopt_motion_planner.cpp b/tesseract_motion_planners/trajopt/src/trajopt_motion_planner.cpp index be88f59cb3..2cd3e796e1 100644 --- a/tesseract_motion_planners/trajopt/src/trajopt_motion_planner.cpp +++ b/tesseract_motion_planners/trajopt/src/trajopt_motion_planner.cpp @@ -163,7 +163,7 @@ PlannerResponse TrajOptMotionPlanner::solve(const PlannerRequest& request) const // Flatten the results to make them easier to process response.results = request.instructions; auto results_instructions = response.results.flatten(&moveFilter); - assert(results_instructions.size() == traj.rows()); + assert(static_cast(results_instructions.size()) == traj.rows()); for (std::size_t idx = 0; idx < results_instructions.size(); idx++) { auto& move_instruction = results_instructions.at(idx).get().as(); @@ -248,7 +248,7 @@ TrajOptMotionPlanner::createProblem(const PlannerRequest& request) const std::vector seed_states; seed_states.reserve(move_instructions.size()); - for (int i = 0; i < move_instructions.size(); ++i) + for (int i = 0; i < static_cast(move_instructions.size()); ++i) { const auto& move_instruction = move_instructions[static_cast(i)].get().as(); diff --git a/tesseract_task_composer/CMakeLists.txt b/tesseract_task_composer/CMakeLists.txt index 52f6e9ccc2..8ae7c2095e 100644 --- a/tesseract_task_composer/CMakeLists.txt +++ b/tesseract_task_composer/CMakeLists.txt @@ -11,7 +11,7 @@ endif() find_package(console_bridge REQUIRED) find_package(tesseract_common REQUIRED) -find_package(Boost REQUIRED COMPONENTS headers serialization) +find_package(Boost REQUIRED COMPONENTS serialization) find_package(yaml-cpp REQUIRED) if(NOT TARGET console_bridge::console_bridge) diff --git a/tesseract_task_composer/core/src/task_composer_keys.cpp b/tesseract_task_composer/core/src/task_composer_keys.cpp index ea243423cd..ac7c1aad60 100644 --- a/tesseract_task_composer/core/src/task_composer_keys.cpp +++ b/tesseract_task_composer/core/src/task_composer_keys.cpp @@ -87,7 +87,6 @@ void TaskComposerKeys::serialize(Archive& ar, const unsigned int /*version*/) std::ostream& operator<<(std::ostream& os, const TaskComposerKeys& keys) { - std::size_t cnt{ 0 }; for (const auto& pair : keys.data()) { if (pair.second.index() == 0) @@ -107,7 +106,6 @@ std::ostream& operator<<(std::ostream& os, const TaskComposerKeys& keys) os << "]"; } os << "\\l"; - ++cnt; } return os; diff --git a/tesseract_time_parameterization/ruckig/src/ruckig_trajectory_smoothing.cpp b/tesseract_time_parameterization/ruckig/src/ruckig_trajectory_smoothing.cpp index 79810df7a9..977e9bdb3a 100644 --- a/tesseract_time_parameterization/ruckig/src/ruckig_trajectory_smoothing.cpp +++ b/tesseract_time_parameterization/ruckig/src/ruckig_trajectory_smoothing.cpp @@ -288,7 +288,7 @@ bool RuckigTrajectorySmoothing::compute(TrajectoryContainer& trajectory, bool smoothing_complete{ false }; while ((duration_extension_factor < max_duration_extension_factor_) && !smoothing_complete) { - for (Eigen::Index waypoint_idx = 0; waypoint_idx < num_waypoints - 1; ++waypoint_idx) + for (Eigen::Index waypoint_idx = 0; waypoint_idx < static_cast(num_waypoints) - 1; ++waypoint_idx) { // Get Next Input getNextRuckigInput( @@ -297,7 +297,7 @@ bool RuckigTrajectorySmoothing::compute(TrajectoryContainer& trajectory, // Run Ruckig ruckig_result = ruckig_ptr->update(ruckig_input, ruckig_output); - if ((waypoint_idx == num_waypoints - 2) && ruckig_result == ruckig::Result::Finished) + if ((waypoint_idx == static_cast(num_waypoints) - 2) && ruckig_result == ruckig::Result::Finished) { smoothing_complete = true; break; @@ -310,7 +310,8 @@ bool RuckigTrajectorySmoothing::compute(TrajectoryContainer& trajectory, Eigen::VectorXd new_duration_from_previous = original_duration_from_previous; double time_from_start = original_duration_from_previous(0); - for (Eigen::Index time_stretch_idx = 1; time_stretch_idx < num_waypoints; ++time_stretch_idx) + for (Eigen::Index time_stretch_idx = 1; time_stretch_idx < static_cast(num_waypoints); + ++time_stretch_idx) { assert(time_stretch_idx < original_duration_from_previous.rows()); const double duration_from_previous = diff --git a/tesseract_time_parameterization/totg/src/time_optimal_trajectory_generation.cpp b/tesseract_time_parameterization/totg/src/time_optimal_trajectory_generation.cpp index f1aa6cc88b..d80772d11e 100644 --- a/tesseract_time_parameterization/totg/src/time_optimal_trajectory_generation.cpp +++ b/tesseract_time_parameterization/totg/src/time_optimal_trajectory_generation.cpp @@ -932,7 +932,7 @@ double Trajectory::getDuration() const { return trajectory_.back().time_; } bool Trajectory::assignData(TrajectoryContainer& trajectory, const std::vector& mapping) const { const auto& dist_mapping = path_.getMapping(); - assert(trajectory.size() == mapping.size()); + assert(trajectory.size() == static_cast(mapping.size())); // Set Start PathData path_data = getPathData(0);