Skip to content

Commit e90be19

Browse files
committed
Adding near-complete voxel grid test coverage and more to controller server (#1915)
* remove erraneous handling done by prior * adding a bunch of voxel unit tests * retrigger
1 parent 33ecb85 commit e90be19

File tree

4 files changed

+49
-15
lines changed

4 files changed

+49
-15
lines changed

nav2_controller/include/nav2_controller/nav2_controller.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -189,6 +189,12 @@ class ControllerServer : public nav2_util::LifecycleNode
189189
return twist_thresh;
190190
}
191191

192+
void pluginFailed(const std::string & name, const pluginlib::PluginlibException & ex)
193+
{
194+
RCLCPP_FATAL(get_logger(), "Failed to create %s. Exception: %s", name.c_str(), ex.what());
195+
exit(-1);
196+
}
197+
192198
// The controller needs a costmap node
193199
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
194200
std::unique_ptr<nav2_util::NodeThread> costmap_thread_;

nav2_controller/src/nav2_controller.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -111,8 +111,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
111111
progress_checker_id_.c_str(), progress_checker_type_.c_str());
112112
progress_checker_->initialize(node, progress_checker_id_);
113113
} catch (const pluginlib::PluginlibException & ex) {
114-
RCLCPP_FATAL(get_logger(), "Failed to create controller. Exception: %s", ex.what());
115-
exit(-1);
114+
pluginFailed("progress_checker", ex);
116115
}
117116
try {
118117
goal_checker_type_ = nav2_util::get_plugin_type_param(node, goal_checker_id_);
@@ -122,8 +121,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
122121
goal_checker_id_.c_str(), goal_checker_type_.c_str());
123122
goal_checker_->initialize(node, goal_checker_id_);
124123
} catch (const pluginlib::PluginlibException & ex) {
125-
RCLCPP_FATAL(get_logger(), "Failed to create controller. Exception: %s", ex.what());
126-
exit(-1);
124+
pluginFailed("goal_checker", ex);
127125
}
128126

129127
for (size_t i = 0; i != controller_ids_.size(); i++) {
@@ -139,8 +137,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
139137
costmap_ros_->getTfBuffer(), costmap_ros_);
140138
controllers_.insert({controller_ids_[i], controller});
141139
} catch (const pluginlib::PluginlibException & ex) {
142-
RCLCPP_FATAL(get_logger(), "Failed to create controller. Exception: %s", ex.what());
143-
exit(-1);
140+
pluginFailed("controller", ex);
144141
}
145142
}
146143

nav2_planner/src/planner_server.cpp

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -292,15 +292,6 @@ PlannerServer::computePlan()
292292
// for example: couldn't get costmap update
293293
action_server_->terminate_current();
294294
return;
295-
} catch (...) {
296-
RCLCPP_WARN(
297-
get_logger(), "Plan calculation failed, "
298-
"An unexpected error has occurred. The planner server"
299-
" may not be able to continue operating correctly.");
300-
// TODO(orduno): provide information about fail error to parent task,
301-
// for example: couldn't get costmap update
302-
action_server_->terminate_current();
303-
return;
304295
}
305296
}
306297

nav2_voxel_grid/test/voxel_grid_tests.cpp

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,46 @@ TEST(voxel_grid, InvalidSize) {
147147
EXPECT_TRUE(vg.getVoxelColumn(50, 11, 0, 0) == nav2_voxel_grid::VoxelStatus::UNKNOWN);
148148
}
149149

150+
TEST(voxel_grid, MarkAndClear) {
151+
int size_x = 10, size_y = 10, size_z = 10;
152+
nav2_voxel_grid::VoxelGrid vg(size_x, size_y, size_z);
153+
vg.markVoxelInMap(5, 5, 5, 0);
154+
EXPECT_EQ(vg.getVoxel(5, 5, 5), nav2_voxel_grid::MARKED);
155+
vg.clearVoxelColumn(55);
156+
EXPECT_EQ(vg.getVoxel(5, 5, 5), nav2_voxel_grid::FREE);
157+
}
158+
159+
TEST(voxel_grid, clearVoxelLineInMap) {
160+
int size_x = 10, size_y = 10, size_z = 10;
161+
nav2_voxel_grid::VoxelGrid vg(size_x, size_y, size_z);
162+
vg.markVoxelInMap(0, 0, 5, 0);
163+
EXPECT_EQ(vg.getVoxel(0, 0, 5), nav2_voxel_grid::MARKED);
164+
165+
unsigned char * map_2d = new unsigned char[100];
166+
map_2d[0] = 254;
167+
168+
vg.clearVoxelLineInMap(0, 0, 0, 0, 0, 9, map_2d, 16, 0);
169+
170+
EXPECT_EQ(map_2d[0], 0);
171+
172+
vg.markVoxelInMap(0, 0, 5, 0);
173+
vg.clearVoxelLineInMap(0, 0, 0, 0, 0, 9, nullptr, 16, 0);
174+
EXPECT_EQ(vg.getVoxel(0, 0, 5), nav2_voxel_grid::FREE);
175+
delete[] map_2d;
176+
}
177+
178+
TEST(voxel_grid, GetVoxelData) {
179+
uint32_t * data = new uint32_t[9];
180+
data[4] = 255;
181+
data[0] = 0;
182+
EXPECT_EQ(
183+
nav2_voxel_grid::VoxelGrid::getVoxel(1, 1, 1, 3, 3, 3, data), nav2_voxel_grid::UNKNOWN);
184+
185+
EXPECT_EQ(
186+
nav2_voxel_grid::VoxelGrid::getVoxel(0, 0, 0, 3, 3, 3, data), nav2_voxel_grid::FREE);
187+
delete[] data;
188+
}
189+
150190
int main(int argc, char ** argv)
151191
{
152192
testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)