Skip to content

Commit

Permalink
minor changes to lower redundent warnings (#1918)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski committed Aug 11, 2020
1 parent d57da0d commit 0cf409a
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 4 deletions.
1 change: 0 additions & 1 deletion nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -416,7 +416,6 @@ bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
{
geometry_msgs::msg::PoseStamped current_pose;
if (!costmap_ros_->getRobotPose(current_pose)) {
RCLCPP_ERROR(this->get_logger(), "Could not get robot pose");
return false;
}
pose = current_pose;
Expand Down
4 changes: 1 addition & 3 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,12 +281,10 @@ PlannerServer::computePlan()
result->planning_time = cycle_duration;

if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
auto planner_period = 1 / max_planner_duration_;
auto cycle_period = 1 / cycle_duration.seconds();
RCLCPP_WARN(
get_logger(),
"Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
planner_period, cycle_period);
1 / max_planner_duration_, 1 / cycle_duration.seconds());
}

action_server_->succeeded_current(result);
Expand Down
1 change: 1 addition & 0 deletions nav2_system_tests/src/waypoint_follower/tester.py
Original file line number Diff line number Diff line change
Expand Up @@ -202,6 +202,7 @@ def main(argv=sys.argv[1:]):
test.cancel_goal()

# a failure case
time.sleep(2)
test.setWaypoints([[100.0, 100.0]])
result = test.run(True)
assert not result
Expand Down

0 comments on commit 0cf409a

Please sign in to comment.