Skip to content

Commit

Permalink
Fix clang-tidy warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Dec 22, 2024
1 parent 3cd567e commit b4a3709
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
7 changes: 4 additions & 3 deletions core/src/solvers/pipeline_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ bool PipelinePlanner::setPlannerId(const std::string& pipeline_name, const std::
return false;
}
it->second = planner_id;
properties().set("pipeline_id_planner_id_map", std::move(map));
properties().set("pipeline_id_planner_id_map", map);
return true;
}

Expand All @@ -111,11 +111,12 @@ void PipelinePlanner::init(const core::RobotModelConstPtr& robot_model) {
}

std::vector<std::string> pipeline_names;
pipeline_names.reserve(map.size());
for (const auto& pipeline_name_planner_id_pair : map) {
pipeline_names.push_back(pipeline_name_planner_id_pair.first);
}
planning_pipelines_ = moveit::planning_pipeline_interfaces::createPlanningPipelineMap(std::move(pipeline_names),
robot_model, node_);
planning_pipelines_ =
moveit::planning_pipeline_interfaces::createPlanningPipelineMap(pipeline_names, robot_model, node_);
// Check if it is still empty
if (planning_pipelines_.empty()) {
throw std::runtime_error("Failed to initialize PipelinePlanner: Could not create any valid pipeline");
Expand Down
2 changes: 1 addition & 1 deletion core/test/test_move_relative.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ constexpr double EPS{ 5e-5 };
template <typename Planner>
std::shared_ptr<Planner> create(const rclcpp::Node::SharedPtr&);
template <>
solvers::CartesianPathPtr create<solvers::CartesianPath>(const rclcpp::Node::SharedPtr&) {
solvers::CartesianPathPtr create<solvers::CartesianPath>(const rclcpp::Node::SharedPtr& /*unused*/) {
return std::make_shared<solvers::CartesianPath>();
}
template <>
Expand Down

0 comments on commit b4a3709

Please sign in to comment.