Skip to content

Commit

Permalink
Fix spin recovery test (#2684)
Browse files Browse the repository at this point in the history
* debugging flaky shutdown on plugin planner tests

* adding independent tests

* adding types

* adding new QoS and fix param declares

* try this

* try tihis

* try 10hz

* try sleeping on setup

* add footprint pub

* adding additional pub for debug

* try adding a spin for debug types

* replacing spin with sleep
  • Loading branch information
SteveMacenski authored Nov 18, 2021
1 parent 46397a3 commit 3f0932f
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ bool SpinRecoveryTester::defaultSpinRecoveryTest(
sendFakeOdom(0.0);
}

rclcpp::spin_some(node_);
rclcpp::sleep_for(std::chrono::milliseconds(100));

auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);

Expand Down Expand Up @@ -328,7 +328,7 @@ void SpinRecoveryTester::sendFakeOdom(float angle)

geometry_msgs::msg::PolygonStamped footprint;
footprint.header.frame_id = "odom";
footprint.header.stamp = rclcpp::Time();
footprint.header.stamp = node_->now();
footprint.polygon.points.resize(4);
footprint.polygon.points[0].x = 0.22;
footprint.polygon.points[0].y = 0.22;
Expand Down

0 comments on commit 3f0932f

Please sign in to comment.