Skip to content

Commit 35b0ce5

Browse files
committed
opennav_coverage - fix tests for fields2cover v2
* fields2cover now initialises memory and provides getters/setters so previous incorrectly/partially initialised data no longer throws * Order of args for f2c::Random::generateRandField() changed to (area, sides), was (sides, area). Tests now don't spin forever Signed-off-by: Mike Wake <[email protected]>
1 parent e2d89e1 commit 35b0ce5

File tree

6 files changed

+20
-8
lines changed

6 files changed

+20
-8
lines changed

opennav_coverage/test/test_headland.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,9 @@ TEST(HeadlandTests, TestheadlandGeneration)
8080

8181
// Generate some toy field
8282
f2c::Random rand;
83-
auto field = rand.generateRandField(5, 1e5);
83+
double area = 1e5;
84+
int sides = 5;
85+
auto field = rand.generateRandField(area, sides);
8486

8587
// Shouldn't throw, results in valid output
8688
opennav_coverage_msgs::msg::HeadlandMode settings;

opennav_coverage/test/test_path.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,9 @@ TEST(PathTests, TestpathGeneration)
114114

115115
// Generate some toy route
116116
f2c::Random rand;
117-
auto field = rand.generateRandField(5, 1e5);
117+
double area = 1e5;
118+
int sides = 5;
119+
auto field = rand.generateRandField(area, sides);
118120
opennav_coverage_msgs::msg::SwathMode sw_settings;
119121
auto swaths = swath_gen.generateSwaths(field.getField().getGeometry(0), sw_settings);
120122
opennav_coverage_msgs::msg::RouteMode rt_settings;

opennav_coverage/test/test_route.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,9 @@ TEST(RouteTests, TestrouteGeneration)
9999

100100
// Generate some toy field
101101
f2c::Random rand;
102-
auto field = rand.generateRandField(5, 1e5);
102+
double area = 1e5;
103+
int sides = 5;
104+
auto field = rand.generateRandField(area, sides);
103105
auto swaths = swath_gen.generateSwaths(field.getField().getGeometry(0), sw_settings);
104106

105107
// Shouldn't throw, results in valid output

opennav_coverage/test/test_swath.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,9 @@ TEST(SwathTests, TestswathGeneration)
108108

109109
// Generate some toy field
110110
f2c::Random rand;
111-
auto field = rand.generateRandField(5, 1e5);
111+
double area = 1e5;
112+
int sides = 5;
113+
auto field = rand.generateRandField(area, sides);
112114

113115
// Shouldn't throw, results in valid output
114116
opennav_coverage_msgs::msg::SwathMode settings;

opennav_coverage/test/test_utils.cpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -106,11 +106,14 @@ TEST(UtilsTests, TesttoNavPathMsg)
106106
header_in.frame_id = "test";
107107
Path path_in;
108108
path_in.getStates().resize(10);
109+
EXPECT_EQ(path_in.size(), 10u);
109110
F2CField field;
110111

111112
auto msg = util::toNavPathMsg(path_in, field, header_in, true, 0.1);
112113
EXPECT_EQ(msg.header.frame_id, "test");
113-
EXPECT_EQ(msg.poses.size(), 10u);
114+
115+
// Path goes nowhere so compressed into a dense path
116+
EXPECT_EQ(msg.poses.size(), 1u);
114117
}
115118

116119
TEST(UtilsTests, TesttoCoveragePathMsg2)
@@ -126,9 +129,10 @@ TEST(UtilsTests, TesttoCoveragePathMsg2)
126129
EXPECT_EQ(msg.contains_turns, true);
127130
EXPECT_EQ(msg.swaths_ordered, true);
128131

129-
// states are not valid (e.g. non-marked as turn or swath)
132+
// states are initalised as a valid swath
130133
path_in.getStates().resize(10);
131-
EXPECT_THROW(util::toCoveragePathMsg(path_in, field, header_in, true), std::runtime_error);
134+
msg = util::toCoveragePathMsg(path_in, field, header_in, true);
135+
util::toCoveragePathMsg(path_in, field, header_in, true);
132136

133137
// Now lets make it valid
134138
using f2c::types::PathSectionType;

opennav_row_coverage/test/test_server.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ TEST(ServerTest, testDynamicParams)
132132
node->get_node_services_interface());
133133

134134
auto results = rec_param->set_parameters_atomically(
135-
{rclcpp::Parameter("default_turn_point_distance", 0.25),
135+
{rclcpp::Parameter("default_turn_point_distance", 0.25), // Discretization ??
136136
rclcpp::Parameter("robot_width", 1.0),
137137
rclcpp::Parameter("operation_width", 1.12),
138138
rclcpp::Parameter("default_path_type", std::string("hi")),

0 commit comments

Comments
 (0)