Skip to content

Commit 83a7bc5

Browse files
committed
minor changes to lower redundent warnings (#1918)
1 parent b7f5e71 commit 83a7bc5

File tree

3 files changed

+2
-4
lines changed

3 files changed

+2
-4
lines changed

nav2_controller/src/nav2_controller.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -424,7 +424,6 @@ bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
424424
{
425425
geometry_msgs::msg::PoseStamped current_pose;
426426
if (!costmap_ros_->getRobotPose(current_pose)) {
427-
RCLCPP_ERROR(this->get_logger(), "Could not get robot pose");
428427
return false;
429428
}
430429
pose = current_pose;

nav2_planner/src/planner_server.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -288,12 +288,10 @@ PlannerServer::computePlan()
288288
result->planning_time = cycle_duration;
289289

290290
if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
291-
auto planner_period = 1 / max_planner_duration_;
292-
auto cycle_period = 1 / cycle_duration.seconds();
293291
RCLCPP_WARN(
294292
get_logger(),
295293
"Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
296-
planner_period, cycle_period);
294+
1 / max_planner_duration_, 1 / cycle_duration.seconds());
297295
}
298296

299297
action_server_->succeeded_current(result);

nav2_system_tests/src/waypoint_follower/tester.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -202,6 +202,7 @@ def main(argv=sys.argv[1:]):
202202
test.cancel_goal()
203203

204204
# a failure case
205+
time.sleep(2)
205206
test.setWaypoints([[100.0, 100.0]])
206207
result = test.run(True)
207208
assert not result

0 commit comments

Comments
 (0)