Skip to content

Commit

Permalink
Fix build warnings
Browse files Browse the repository at this point in the history
I tried to build the avoidance repo just now, and the build failed
with clang. The error in clang is just a warning in gcc, so gcc builds,
but with warnings. I've taken the warnings reported by both clang and
gcc, and tried to fix them.

The issues were

* assigning from an uninitialized variable,
* reaching the end of a non-void function, and
* passing a std::string to a "%s" specifier (expects char*).
  • Loading branch information
mortenfyhn authored and jkflying committed Aug 7, 2020
1 parent 3cae2aa commit 273eb7e
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 8 deletions.
10 changes: 5 additions & 5 deletions global_planner/include/global_planner/global_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,11 +64,6 @@ class GlobalPlanner {
GoalCell goal_pos_ = GoalCell(0.5, 0.5, 3.5);
bool going_back_ = true; // we start by just finding the start position

double overestimate_factor_ = max_overestimate_factor_;
std::vector<Cell> curr_path_;
PathInfo curr_path_info_;
SearchVisitor<std::unordered_set<Cell>, std::unordered_map<Cell, double> > visitor_;

// Dynamic reconfigure parameters
int min_altitude_ = 1;
int max_altitude_ = 10;
Expand All @@ -94,6 +89,11 @@ class GlobalPlanner {
std::string default_node_type_ = "SpeedNode";
std::string frame_id_ = "world";

double overestimate_factor_ = max_overestimate_factor_;
std::vector<Cell> curr_path_;
PathInfo curr_path_info_;
SearchVisitor<std::unordered_set<Cell>, std::unordered_map<Cell, double> > visitor_;

GlobalPlanner();
~GlobalPlanner();

Expand Down
3 changes: 1 addition & 2 deletions global_planner/include/global_planner/global_planner_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,7 @@ class GlobalPlannerNode {
double cmdloop_dt_;
double plannerloop_dt_;
double mapupdate_dt_;
double min_speed_;
double speed_ = min_speed_;
double speed_;
double start_yaw_;
bool position_received_;
std::string frame_id_;
Expand Down
2 changes: 2 additions & 0 deletions global_planner/src/library/global_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -405,6 +405,8 @@ NodePtr GlobalPlanner::getStartNode(const Cell& start, const Cell& parent, const
}
if (type == "SpeedNode") {
return NodePtr(new SpeedNode(start, parent));
} else {
return NodePtr(new Node(start, parent));
}
}

Expand Down
2 changes: 1 addition & 1 deletion global_planner/src/nodes/global_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,7 +292,7 @@ void GlobalPlannerNode::depthCameraCallback(const sensor_msgs::PointCloud2& msg)
pointcloud_pub_.publish(msg);
} catch (tf::TransformException const& ex) {
ROS_DEBUG("%s", ex.what());
ROS_WARN("Transformation not available (%s to /camera_link", frame_id_);
ROS_WARN("Transformation not available (%s to /camera_link)", frame_id_.c_str());
}
}

Expand Down

0 comments on commit 273eb7e

Please sign in to comment.