Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 8 additions & 7 deletions nav2_system_tests/src/behaviors/spin/spin_behavior_tester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,7 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest(
std::this_thread::sleep_for(5s);

if (make_fake_costmap_) {
sendFakeCostmap(target_yaw);
sendFakeOdom(0.0);
}

Expand Down Expand Up @@ -211,7 +212,7 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest(
{
sendFakeOdom(command_yaw);
sendFakeCostmap(target_yaw);
rclcpp::sleep_for(std::chrono::milliseconds(1));
rclcpp::sleep_for(std::chrono::milliseconds(3));
}
sendFakeOdom(target_yaw);
sendFakeCostmap(target_yaw);
Expand Down Expand Up @@ -277,7 +278,7 @@ void SpinBehaviorTester::sendFakeCostmap(float angle)
nav2_msgs::msg::Costmap fake_costmap;

fake_costmap.header.frame_id = "odom";
fake_costmap.header.stamp = stamp_;
fake_costmap.header.stamp = node_->now();
fake_costmap.metadata.layer = "master";
fake_costmap.metadata.resolution = .1;
fake_costmap.metadata.size_x = 100;
Expand All @@ -288,9 +289,9 @@ void SpinBehaviorTester::sendFakeCostmap(float angle)
float costmap_val = 0;
for (int ix = 0; ix < 100; ix++) {
for (int iy = 0; iy < 100; iy++) {
if (abs(angle) > M_PI_2f32) {
if (fabs(angle) > M_PI_2f32) {
// fake obstacles in the way so we get failure due to potential collision
costmap_val = 100;
costmap_val = 253;
}
fake_costmap.data.push_back(costmap_val);
}
Expand All @@ -302,7 +303,7 @@ void SpinBehaviorTester::sendInitialPose()
{
geometry_msgs::msg::PoseWithCovarianceStamped pose;
pose.header.frame_id = "map";
pose.header.stamp = stamp_;
pose.header.stamp = node_->now();
pose.pose.pose.position.x = -2.0;
pose.pose.pose.position.y = -0.5;
pose.pose.pose.position.z = 0.0;
Expand All @@ -325,7 +326,7 @@ void SpinBehaviorTester::sendFakeOdom(float angle)
{
geometry_msgs::msg::TransformStamped transformStamped;

transformStamped.header.stamp = stamp_;
transformStamped.header.stamp = node_->now();
transformStamped.header.frame_id = "odom";
transformStamped.child_frame_id = "base_link";
transformStamped.transform.translation.x = 0.0;
Expand All @@ -342,7 +343,7 @@ void SpinBehaviorTester::sendFakeOdom(float angle)

geometry_msgs::msg::PolygonStamped footprint;
footprint.header.frame_id = "odom";
footprint.header.stamp = stamp_;
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
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,8 @@ def generate_launch_description():
'gzserver',
'-s',
'libgazebo_ros_init.so',
'-s',
'libgazebo_ros_factory.so',
'--minimal_comms',
world,
],
Expand Down
10 changes: 5 additions & 5 deletions nav2_system_tests/src/behaviors/spin/test_spin_behavior_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,12 +118,12 @@ INSTANTIATE_TEST_SUITE_P(
SpinRecoveryTests,
SpinBehaviorTestFixture,
::testing::Values(
std::make_tuple(-M_PIf32 / 6.0, 0.15),
std::make_tuple(M_PI_4f32, 0.15),
std::make_tuple(-M_PI_2f32, 0.15),
std::make_tuple(M_PIf32, 0.10),
std::make_tuple(-M_PIf32 / 6.0, 0.1),
// std::make_tuple(M_PI_4f32, 0.1),
// std::make_tuple(-M_PI_2f32, 0.1),
std::make_tuple(M_PIf32, 0.1),
std::make_tuple(3.0 * M_PIf32 / 2.0, 0.15),
std::make_tuple(-2.0 * M_PIf32, 0.15),
std::make_tuple(-2.0 * M_PIf32, 0.1),
std::make_tuple(4.0 * M_PIf32, 0.15)),
testNameGenerator);

Expand Down