@@ -136,6 +136,7 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest(
136136 std::this_thread::sleep_for (5s);
137137
138138 if (make_fake_costmap_) {
139+ sendFakeCostmap (target_yaw);
139140 sendFakeOdom (0.0 );
140141 }
141142
@@ -211,7 +212,7 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest(
211212 {
212213 sendFakeOdom (command_yaw);
213214 sendFakeCostmap (target_yaw);
214- rclcpp::sleep_for (std::chrono::milliseconds (1 ));
215+ rclcpp::sleep_for (std::chrono::milliseconds (3 ));
215216 }
216217 sendFakeOdom (target_yaw);
217218 sendFakeCostmap (target_yaw);
@@ -277,7 +278,7 @@ void SpinBehaviorTester::sendFakeCostmap(float angle)
277278 nav2_msgs::msg::Costmap fake_costmap;
278279
279280 fake_costmap.header .frame_id = " odom" ;
280- fake_costmap.header .stamp = stamp_ ;
281+ fake_costmap.header .stamp = node_-> now () ;
281282 fake_costmap.metadata .layer = " master" ;
282283 fake_costmap.metadata .resolution = .1 ;
283284 fake_costmap.metadata .size_x = 100 ;
@@ -288,9 +289,9 @@ void SpinBehaviorTester::sendFakeCostmap(float angle)
288289 float costmap_val = 0 ;
289290 for (int ix = 0 ; ix < 100 ; ix++) {
290291 for (int iy = 0 ; iy < 100 ; iy++) {
291- if (abs (angle) > M_PI_2f32) {
292+ if (fabs (angle) > M_PI_2f32) {
292293 // fake obstacles in the way so we get failure due to potential collision
293- costmap_val = 100 ;
294+ costmap_val = 253 ;
294295 }
295296 fake_costmap.data .push_back (costmap_val);
296297 }
@@ -302,7 +303,7 @@ void SpinBehaviorTester::sendInitialPose()
302303{
303304 geometry_msgs::msg::PoseWithCovarianceStamped pose;
304305 pose.header .frame_id = " map" ;
305- pose.header .stamp = stamp_ ;
306+ pose.header .stamp = node_-> now () ;
306307 pose.pose .pose .position .x = -2.0 ;
307308 pose.pose .pose .position .y = -0.5 ;
308309 pose.pose .pose .position .z = 0.0 ;
@@ -325,7 +326,7 @@ void SpinBehaviorTester::sendFakeOdom(float angle)
325326{
326327 geometry_msgs::msg::TransformStamped transformStamped;
327328
328- transformStamped.header .stamp = stamp_ ;
329+ transformStamped.header .stamp = node_-> now () ;
329330 transformStamped.header .frame_id = " odom" ;
330331 transformStamped.child_frame_id = " base_link" ;
331332 transformStamped.transform .translation .x = 0.0 ;
@@ -342,7 +343,7 @@ void SpinBehaviorTester::sendFakeOdom(float angle)
342343
343344 geometry_msgs::msg::PolygonStamped footprint;
344345 footprint.header .frame_id = " odom" ;
345- footprint.header .stamp = stamp_ ;
346+ footprint.header .stamp = node_-> now () ;
346347 footprint.polygon .points .resize (4 );
347348 footprint.polygon .points [0 ].x = 0.22 ;
348349 footprint.polygon .points [0 ].y = 0.22 ;
0 commit comments