Skip to content

Commit

Permalink
Fix Mac OS clang compiler warnings (#496)
Browse files Browse the repository at this point in the history
  • Loading branch information
johnwason authored Aug 1, 2024
1 parent 3b310a6 commit 0a2906e
Show file tree
Hide file tree
Showing 9 changed files with 28 additions and 26 deletions.
6 changes: 4 additions & 2 deletions .github/workflows/mac.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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 }}
Expand All @@ -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 }}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::size_t>(seed.position.size()) == seed.joint_names.size());
}

void tesseract_planning::CartesianWaypointPoly::clearSeed() { getInterface().setSeed(tesseract_common::JointState()); }
Expand Down
26 changes: 13 additions & 13 deletions tesseract_motion_planners/simple/src/interpolation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ std::vector<MoveInstructionPoly> interpolateJointJointWaypoint(const KinematicGr
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -286,7 +286,7 @@ std::vector<MoveInstructionPoly> interpolateJointCartWaypoint(const KinematicGro
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -349,7 +349,7 @@ std::vector<MoveInstructionPoly> interpolateCartJointWaypoint(const KinematicGro
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -451,7 +451,7 @@ std::vector<MoveInstructionPoly> interpolateCartCartWaypoint(const KinematicGrou
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -540,7 +540,7 @@ std::vector<MoveInstructionPoly> interpolateJointCartWaypoint(const KinematicGro
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand All @@ -561,7 +561,7 @@ std::vector<MoveInstructionPoly> interpolateJointCartWaypoint(const KinematicGro
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -618,7 +618,7 @@ std::vector<MoveInstructionPoly> interpolateCartJointWaypoint(const KinematicGro
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand All @@ -639,7 +639,7 @@ std::vector<MoveInstructionPoly> interpolateCartJointWaypoint(const KinematicGro
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -740,7 +740,7 @@ std::vector<MoveInstructionPoly> interpolateCartCartWaypoint(const KinematicGrou
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -786,7 +786,7 @@ std::vector<MoveInstructionPoly> interpolateJointJointWaypoint(const JointGroupI
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -839,7 +839,7 @@ std::vector<MoveInstructionPoly> interpolateJointCartWaypoint(const JointGroupIn
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -892,7 +892,7 @@ std::vector<MoveInstructionPoly> interpolateCartJointWaypoint(const JointGroupIn
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down Expand Up @@ -948,7 +948,7 @@ std::vector<MoveInstructionPoly> interpolateCartCartWaypoint(const JointGroupIns
for (auto& pose : poses)
pose = base.working_frame_transform.inverse() * pose;

assert(poses.size() == states.cols());
assert(static_cast<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, base.manip->getJointNames(), states, base.instruction);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Eigen::Index>(poses.size()) == states.cols());
return getInterpolatedInstructions(poses, info2.manip->getJointNames(), states, info2.instruction);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Eigen::Index>(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<MoveInstructionPoly>();
Expand Down Expand Up @@ -248,7 +248,7 @@ TrajOptMotionPlanner::createProblem(const PlannerRequest& request) const
std::vector<Eigen::VectorXd> seed_states;
seed_states.reserve(move_instructions.size());

for (int i = 0; i < move_instructions.size(); ++i)
for (int i = 0; i < static_cast<Eigen::Index>(move_instructions.size()); ++i)
{
const auto& move_instruction = move_instructions[static_cast<std::size_t>(i)].get().as<MoveInstructionPoly>();

Expand Down
2 changes: 1 addition & 1 deletion tesseract_task_composer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 0 additions & 2 deletions tesseract_task_composer/core/src/task_composer_keys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -107,7 +106,6 @@ std::ostream& operator<<(std::ostream& os, const TaskComposerKeys& keys)
os << "]";
}
os << "\\l";
++cnt;
}

return os;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Eigen::Index>(num_waypoints) - 1; ++waypoint_idx)
{
// Get Next Input
getNextRuckigInput(
Expand All @@ -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<Eigen::Index>(num_waypoints) - 2) && ruckig_result == ruckig::Result::Finished)
{
smoothing_complete = true;
break;
Expand All @@ -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<Eigen::Index>(num_waypoints);
++time_stretch_idx)
{
assert(time_stretch_idx < original_duration_from_previous.rows());
const double duration_from_previous =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -932,7 +932,7 @@ double Trajectory::getDuration() const { return trajectory_.back().time_; }
bool Trajectory::assignData(TrajectoryContainer& trajectory, const std::vector<std::size_t>& mapping) const
{
const auto& dist_mapping = path_.getMapping();
assert(trajectory.size() == mapping.size());
assert(trajectory.size() == static_cast<Eigen::Index>(mapping.size()));

// Set Start
PathData path_data = getPathData(0);
Expand Down

0 comments on commit 0a2906e

Please sign in to comment.