Skip to content

Commit b4c2925

Browse files
author
asarazin
committed
add tests
Signed-off-by: asarazin <[email protected]>
1 parent 2d55ca7 commit b4c2925

File tree

3 files changed

+130
-11
lines changed

3 files changed

+130
-11
lines changed

nav2_collision_monitor/test/collision_monitor_node_test.cpp

Lines changed: 55 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -143,7 +143,8 @@ class Tester : public ::testing::Test
143143
void setCommonParameters();
144144
void addPolygon(
145145
const std::string & polygon_name, const PolygonType type,
146-
const double size, const std::string & at);
146+
const double size, const std::string & at,
147+
const std::vector<std::string> & sources_names = std::vector<std::string>());
147148
void addPolygonVelocitySubPolygon(
148149
const std::string & polygon_name, const std::string & sub_polygon_name,
149150
const double linear_min, const double linear_max,
@@ -309,7 +310,8 @@ void Tester::setCommonParameters()
309310

310311
void Tester::addPolygon(
311312
const std::string & polygon_name, const PolygonType type,
312-
const double size, const std::string & at)
313+
const double size, const std::string & at,
314+
const std::vector<std::string> & sources_names)
313315
{
314316
if (type == POLYGON) {
315317
cm_->declare_parameter(
@@ -408,6 +410,13 @@ void Tester::addPolygon(
408410
polygon_name + ".polygon_pub_topic", rclcpp::ParameterValue(polygon_name));
409411
cm_->set_parameter(
410412
rclcpp::Parameter(polygon_name + ".polygon_pub_topic", polygon_name));
413+
414+
if (!sources_names.empty()) {
415+
cm_->declare_parameter(
416+
polygon_name + ".sources_names", rclcpp::ParameterValue(sources_names));
417+
cm_->set_parameter(
418+
rclcpp::Parameter(polygon_name + ".sources_names", sources_names));
419+
}
411420
}
412421

413422
void Tester::addPolygonVelocitySubPolygon(
@@ -1499,9 +1508,10 @@ TEST_F(Tester, testCollisionPointsMarkers)
14991508
// Share TF
15001509
sendTransforms(curr_time);
15011510

1511+
// No source published, empty marker array published
15021512
publishCmdVel(0.5, 0.2, 0.1);
15031513
ASSERT_TRUE(waitCollisionPointsMarker(500ms));
1504-
ASSERT_EQ(collision_points_marker_msg_->markers[0].points.size(), 0u);
1514+
ASSERT_EQ(collision_points_marker_msg_->markers.size(), 0u);
15051515

15061516
publishScan(0.5, curr_time);
15071517
ASSERT_TRUE(waitData(0.5, 500ms, curr_time));
@@ -1580,6 +1590,48 @@ TEST_F(Tester, testVelocityPolygonStop)
15801590
cm_->stop();
15811591
}
15821592

1593+
TEST_F(Tester, testSourceAssociatedToPolygon)
1594+
{
1595+
// Set Collision Monitor parameters:
1596+
// - 2 sources (scan and range)
1597+
// - 1 stop polygon associated to range source
1598+
// - 1 slowdown polygon (associated with all sources by default)
1599+
setCommonParameters();
1600+
addSource(SCAN_NAME, SCAN);
1601+
addSource(RANGE_NAME, RANGE);
1602+
std::vector<std::string> range_only_sources_names = {RANGE_NAME};
1603+
std::vector<std::string> all_sources_names = {SCAN_NAME, RANGE_NAME};
1604+
addPolygon("StopOnRangeSource", POLYGON, 1.0, "stop", range_only_sources_names);
1605+
addPolygon("SlowdownOnAllSources", POLYGON, 1.0, "slowdown");
1606+
setVectors({"StopOnRangeSource", "SlowdownOnAllSources"}, {SCAN_NAME, RANGE_NAME});
1607+
1608+
// Start Collision Monitor node
1609+
cm_->start();
1610+
1611+
// Share TF
1612+
rclcpp::Time curr_time = cm_->now();
1613+
sendTransforms(curr_time);
1614+
1615+
// Publish sources so that :
1616+
// - scan obstacle is in polygons
1617+
// - range obstacle is far away from polygons
1618+
publishScan(0.5, curr_time);
1619+
publishRange(4.5, curr_time);
1620+
ASSERT_TRUE(waitData(0.5, 500ms, curr_time));
1621+
1622+
// Publish cmd vel
1623+
publishCmdVel(0.5, 0.0, 0.0);
1624+
ASSERT_TRUE(waitCmdVel(500ms));
1625+
1626+
// Since the stop polygon is only checking range source, slowdown action should be applied
1627+
ASSERT_TRUE(waitActionState(500ms));
1628+
ASSERT_EQ(action_state_->action_type, SLOWDOWN);
1629+
ASSERT_EQ(action_state_->polygon_name, "SlowdownOnAllSources");
1630+
1631+
// Stop Collision Monitor node
1632+
cm_->stop();
1633+
}
1634+
15831635
int main(int argc, char ** argv)
15841636
{
15851637
// Initialize the system

nav2_collision_monitor/test/polygons_test.cpp

Lines changed: 69 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ static const char POLYGON_SUB_TOPIC[]{"polygon_sub"};
4646
static const char POLYGON_PUB_TOPIC[]{"polygon_pub"};
4747
static const char POLYGON_NAME[]{"TestPolygon"};
4848
static const char CIRCLE_NAME[]{"TestCircle"};
49+
static const char OBSERVATION_SOURCE_NAME[]{"source"};
4950
static const std::vector<double> SQUARE_POLYGON {
5051
0.5, 0.5, 0.5, -0.5, -0.5, -0.5, -0.5, 0.5};
5152
static const std::vector<double> ARBITRARY_POLYGON {
@@ -235,7 +236,11 @@ class Tester : public ::testing::Test
235236

236237
protected:
237238
// Working with parameters
238-
void setCommonParameters(const std::string & polygon_name, const std::string & action_type);
239+
void setCommonParameters(
240+
const std::string & polygon_name, const std::string & action_type,
241+
const std::vector<std::string> & observation_sources =
242+
std::vector<std::string>({OBSERVATION_SOURCE_NAME}),
243+
const std::vector<std::string> & sources_names = std::vector<std::string>());
239244
void setPolygonParameters(
240245
const char * points,
241246
const bool is_static);
@@ -289,7 +294,10 @@ Tester::~Tester()
289294
tf_buffer_.reset();
290295
}
291296

292-
void Tester::setCommonParameters(const std::string & polygon_name, const std::string & action_type)
297+
void Tester::setCommonParameters(
298+
const std::string & polygon_name, const std::string & action_type,
299+
const std::vector<std::string> & observation_sources,
300+
const std::vector<std::string> & sources_names)
293301
{
294302
test_node_->declare_parameter(
295303
polygon_name + ".action_type", rclcpp::ParameterValue(action_type));
@@ -336,6 +344,18 @@ void Tester::setCommonParameters(const std::string & polygon_name, const std::st
336344
polygon_name + ".polygon_pub_topic", rclcpp::ParameterValue(POLYGON_PUB_TOPIC));
337345
test_node_->set_parameter(
338346
rclcpp::Parameter(polygon_name + ".polygon_pub_topic", POLYGON_PUB_TOPIC));
347+
348+
test_node_->declare_parameter(
349+
"observation_sources", rclcpp::ParameterValue(observation_sources));
350+
test_node_->set_parameter(
351+
rclcpp::Parameter("observation_sources", observation_sources));
352+
353+
if (!sources_names.empty()) {
354+
test_node_->declare_parameter(
355+
polygon_name + ".sources_names", rclcpp::ParameterValue(sources_names));
356+
test_node_->set_parameter(
357+
rclcpp::Parameter(polygon_name + ".sources_names", sources_names));
358+
}
339359
}
340360

341361
void Tester::setPolygonParameters(
@@ -863,23 +883,23 @@ TEST_F(Tester, testPolygonGetCollisionTime)
863883
nav2_collision_monitor::Velocity vel{0.5, 0.0, 0.0}; // 0.5 m/s forward movement
864884
// Two points 0.2 m ahead the footprint (0.5 m)
865885
std::unordered_map<std::string, std::vector<nav2_collision_monitor::Point>> points_map;
866-
points_map.insert({"source", {{0.7, -0.01}, {0.7, 0.01}}});
886+
points_map.insert({OBSERVATION_SOURCE_NAME, {{0.7, -0.01}, {0.7, 0.01}}});
867887
// Collision is expected to be ~= 0.2 m / 0.5 m/s seconds
868888
EXPECT_NEAR(polygon_->getCollisionTime(points_map, vel), 0.4, SIMULATION_TIME_STEP);
869889

870890
// Backward movement check
871891
vel = {-0.5, 0.0, 0.0}; // 0.5 m/s backward movement
872892
// Two points 0.2 m behind the footprint (0.5 m)
873893
points_map.clear();
874-
points_map.insert({"source", {{-0.7, -0.01}, {-0.7, 0.01}}});
894+
points_map.insert({OBSERVATION_SOURCE_NAME, {{-0.7, -0.01}, {-0.7, 0.01}}});
875895
// Collision is expected to be in ~= 0.2 m / 0.5 m/s seconds
876896
EXPECT_NEAR(polygon_->getCollisionTime(points_map, vel), 0.4, SIMULATION_TIME_STEP);
877897

878898
// Sideway movement check
879899
vel = {0.0, 0.5, 0.0}; // 0.5 m/s sideway movement
880900
// Two points 0.1 m ahead the footprint (0.5 m)
881901
points_map.clear();
882-
points_map.insert({"source", {{-0.01, 0.6}, {0.01, 0.6}}});
902+
points_map.insert({OBSERVATION_SOURCE_NAME, {{-0.01, 0.6}, {0.01, 0.6}}});
883903
// Collision is expected to be in ~= 0.1 m / 0.5 m/s seconds
884904
EXPECT_NEAR(polygon_->getCollisionTime(points_map, vel), 0.2, SIMULATION_TIME_STEP);
885905

@@ -896,7 +916,7 @@ TEST_F(Tester, testPolygonGetCollisionTime)
896916
// -----------
897917
// '
898918
points_map.clear();
899-
points_map.insert({"source", {{0.49, -0.01}, {0.49, 0.01}}});
919+
points_map.insert({OBSERVATION_SOURCE_NAME, {{0.49, -0.01}, {0.49, 0.01}}});
900920
// Collision is expected to be in ~= 45 degrees * M_PI / (180 degrees * 1.0 rad/s) seconds
901921
double exp_res = 45 / 180 * M_PI;
902922
EXPECT_NEAR(polygon_->getCollisionTime(points_map, vel), exp_res, EPSILON);
@@ -905,15 +925,15 @@ TEST_F(Tester, testPolygonGetCollisionTime)
905925
vel = {0.5, 0.0, 0.0}; // 0.5 m/s forward movement
906926
// Two points inside
907927
points_map.clear();
908-
points_map.insert({"source", {{0.1, -0.01}, {0.1, 0.01}}});
928+
points_map.insert({OBSERVATION_SOURCE_NAME, {{0.1, -0.01}, {0.1, 0.01}}});
909929
// Collision already appeared: collision time should be 0
910930
EXPECT_NEAR(polygon_->getCollisionTime(points_map, vel), 0.0, EPSILON);
911931

912932
// All points are out of simulation prediction
913933
vel = {0.5, 0.0, 0.0}; // 0.5 m/s forward movement
914934
// Two points 0.6 m ahead the footprint (0.5 m)
915935
points_map.clear();
916-
points_map.insert({"source", {{1.1, -0.01}, {1.1, 0.01}}});
936+
points_map.insert({OBSERVATION_SOURCE_NAME, {{1.1, -0.01}, {1.1, 0.01}}});
917937
// There is no collision: return value should be negative
918938
EXPECT_LT(polygon_->getCollisionTime(points_map, vel), 0.0);
919939
}
@@ -946,6 +966,9 @@ TEST_F(Tester, testPolygonDefaultVisualize)
946966
std::string(POLYGON_NAME) + ".action_type", rclcpp::ParameterValue("stop"));
947967
test_node_->set_parameter(
948968
rclcpp::Parameter(std::string(POLYGON_NAME) + ".action_type", "stop"));
969+
std::vector<std::string> observation_sources = {OBSERVATION_SOURCE_NAME};
970+
test_node_->declare_parameter("observation_sources", rclcpp::ParameterValue(observation_sources));
971+
test_node_->set_parameter(rclcpp::Parameter("observation_sources", observation_sources));
949972
setPolygonParameters(SQUARE_POLYGON_STR, true);
950973

951974
// Create new polygon
@@ -978,6 +1001,44 @@ TEST_F(Tester, testPolygonInvalidPointsString)
9781001
ASSERT_FALSE(polygon_->configure());
9791002
}
9801003

1004+
TEST_F(Tester, testPolygonSourceDefaultAssociation)
1005+
{
1006+
// By default, a polygon uses all observation sources
1007+
std::vector<std::string> all_sources = {"source_1", "source_2", "source_3"};
1008+
setCommonParameters(POLYGON_NAME, "stop", all_sources); // no polygon sources names specified
1009+
setPolygonParameters(SQUARE_POLYGON_STR, true);
1010+
polygon_ = std::make_shared<PolygonWrapper>(
1011+
test_node_, POLYGON_NAME,
1012+
tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE);
1013+
ASSERT_TRUE(polygon_->configure());
1014+
ASSERT_EQ(polygon_->getSourcesNames(), all_sources);
1015+
}
1016+
1017+
TEST_F(Tester, testPolygonSourceInvalidAssociation)
1018+
{
1019+
// If a source is not defined as observation source, polygon cannot use it: config should fail
1020+
setCommonParameters(
1021+
POLYGON_NAME, "stop", {"source_1", "source_2", "source_3"}, {"source_1", "source_4"});
1022+
setPolygonParameters(SQUARE_POLYGON_STR, true);
1023+
polygon_ = std::make_shared<PolygonWrapper>(
1024+
test_node_, POLYGON_NAME,
1025+
tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE);
1026+
ASSERT_FALSE(polygon_->configure());
1027+
}
1028+
1029+
TEST_F(Tester, testPolygonSourceAssociation)
1030+
{
1031+
// Checks that, if declared, only the specific sources associated to polygon are saved
1032+
std::vector<std::string> poly_sources = {"source_1", "source_3"};
1033+
setCommonParameters(POLYGON_NAME, "stop", {"source_1", "source_2", "source_3"}, poly_sources);
1034+
setPolygonParameters(SQUARE_POLYGON_STR, true);
1035+
polygon_ = std::make_shared<PolygonWrapper>(
1036+
test_node_, POLYGON_NAME,
1037+
tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE);
1038+
ASSERT_TRUE(polygon_->configure());
1039+
ASSERT_EQ(polygon_->getSourcesNames(), poly_sources);
1040+
}
1041+
9811042
int main(int argc, char ** argv)
9821043
{
9831044
// Initialize the system

nav2_collision_monitor/test/velocity_polygons_test.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -208,6 +208,12 @@ void Tester::setCommonParameters(const std::string & polygon_name, const std::st
208208
polygon_name + ".polygon_pub_topic", rclcpp::ParameterValue(POLYGON_PUB_TOPIC));
209209
test_node_->set_parameter(
210210
rclcpp::Parameter(polygon_name + ".polygon_pub_topic", POLYGON_PUB_TOPIC));
211+
212+
std::vector<std::string> default_observation_sources = {"source"};
213+
test_node_->declare_parameter(
214+
"observation_sources", rclcpp::ParameterValue(default_observation_sources));
215+
test_node_->set_parameter(
216+
rclcpp::Parameter("observation_sources", default_observation_sources));
211217
}
212218

213219
void Tester::setVelocityPolygonParameters(const bool is_holonomic)

0 commit comments

Comments
 (0)