Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Regional Assessment of Risk Using Point Clouds #372

Closed
Closed
Changes from 1 commit
Commits
Show all changes
61 commits
Select commit Hold shift + click to select a range
7bab36e
Risk Analysis structure finished with accompanying rviz publishers
RobynCastro Nov 8, 2018
6cbbb64
Added some unit tests for Risk Analysis
RobynCastro Nov 17, 2018
cbc6530
Added rviz polygon markers
RobynCastro Nov 17, 2018
7848320
Fixed a function javadoc commentfor createPolygonMarker
RobynCastro Nov 17, 2018
9021bc4
Resolved type mismatch in RvizUtils
RobynCastro Nov 17, 2018
7ea488f
Ran fix formatting script
RobynCastro Dec 1, 2018
a6e82c5
Added point equality testing inside multiplePointMarkersTest
RobynCastro Dec 1, 2018
6083b46
Ran fix formatting script
RobynCastro Dec 1, 2018
ae0d4c0
Revert "Revert "Pegged librealsense Version as a Temporary Fix (#359)…
RobynCastro Dec 1, 2018
6ff67fd
Changed setup_realsense realsense version to a working version
RobynCastro Dec 1, 2018
039c048
Updated realsense version
RobynCastro Dec 13, 2018
974a6d5
Merge branch 'master' into robyn/rviz-polygon-markers
RobynCastro Jan 5, 2019
aa8e892
Merge remote-tracking branch 'upstream/master'
RobynCastro Jan 5, 2019
0171bd3
Merge branch 'master' into robyn/rviz-polygon-markers
RobynCastro Jan 5, 2019
9e13c99
Fixed install_tools script
RobynCastro Jan 5, 2019
a5b33b4
Merge branch 'master' into robyn/risk-analysis
RobynCastro Jan 5, 2019
c0ec8f3
Added templating for RvizUtils polygon markers
RobynCastro Jan 5, 2019
c07370d
Fixed RvizUtils templated function
RobynCastro Jan 12, 2019
877d72e
Merge branch 'master' into robyn/rviz-polygon-markers
RobynCastro Jan 19, 2019
800e0cd
added comment to detail why this is a rostest
RobynCastro Jan 19, 2019
b60684b
Added reasoning why rviz_utils uses a rostest
RobynCastro Jan 19, 2019
94fdda0
Fixed merge conflict
RobynCastro Jan 19, 2019
50ec1f8
Templating the polygon risk function
RobynCastro Feb 14, 2019
f148048
Merge remote-tracking branch 'upstream/master' into robyn/rviz-polygo…
RobynCastro Feb 15, 2019
33e3977
Fixed type for createMarkerScale
RobynCastro Feb 15, 2019
5dea15f
Fixed typo in rostest
RobynCastro Feb 15, 2019
2062d32
Fixed determineColumn, determineRow, and added tests, and risk multip…
RobynCastro Feb 15, 2019
322334e
Refactored zed_transform to pcl_transform and added a new param
RobynCastro Feb 15, 2019
6825470
Merge branch 'master' into robyn/pcl-transform
RobynCastro Feb 15, 2019
4ff2c93
Fixed rviz polygon tests to account for cycles
RobynCastro Feb 16, 2019
b2760b0
Fixed merge conflicts
RobynCastro Feb 16, 2019
21353bb
Fixed merge conflicts
RobynCastro Feb 16, 2019
7fbeeb3
Change realsense tranform from base_link to camera_link
RobynCastro Feb 16, 2019
ee7df3b
Fixed output frame_id for pcl_transform
RobynCastro Feb 16, 2019
54d7cab
Merge branch 'robyn/pcl-transform' of https://github.com/RobynCastro/…
RobynCastro Feb 16, 2019
c3f1d99
Merge remote-tracking branch 'upstream/master'
RobynCastro Feb 16, 2019
3e21c8f
Removed the node for rviz_utils_rostest
RobynCastro Feb 16, 2019
06f1553
Fixed file naming inside rviz_utils_rostest
RobynCastro Feb 21, 2019
5c50281
Merge branch 'robyn/rviz-polygon-markers' into robyn/risk-analysis
RobynCastro Feb 21, 2019
ebfd501
Merge branch 'robyn/pcl-transform' into robyn/risk-analysis
RobynCastro Feb 21, 2019
2c52862
Documentation comments
RobynCastro Feb 21, 2019
c6d0fa1
No longer templating and now forcing marker_id specification
RobynCastro Feb 23, 2019
929edc0
Fixed ros_tests to work with sb_geom_msgs::Polygon2D
RobynCastro Feb 23, 2019
5a0bf47
Added more function comments
RobynCastro Feb 23, 2019
dd7916d
Fixed tests, and added more function comments
RobynCastro Feb 23, 2019
7419842
Merge remote-tracking branch 'upstream/master'
RobynCastro Feb 23, 2019
15ef631
Merge branch 'master' into robyn/rviz-polygon-markers
RobynCastro Feb 23, 2019
a15b382
Ran fix formatting
RobynCastro Feb 23, 2019
fc24b5c
Added better tests for region initialisation
RobynCastro Feb 23, 2019
c33c7ec
Merge branch 'master' into robyn/risk-analysis
RobynCastro Feb 23, 2019
5f11cf1
Updated sb_utils to build messages first
RobynCastro Feb 23, 2019
d46bb59
Merge branch 'robyn/rviz-polygon-markers' into robyn/risk-analysis
RobynCastro Mar 2, 2019
010a909
Added transform_period
RobynCastro Mar 2, 2019
2a64755
Added constructor comments
RobynCastro Mar 2, 2019
eac6470
Fixed some documentation inside RiskAnalysis.h
RobynCastro Mar 2, 2019
15c396f
Added more comments for the realsense_transform file
RobynCastro Mar 2, 2019
9ec0dfe
Moved end of file down
RobynCastro Mar 2, 2019
d1a90dd
Merge remote-tracking branch 'upstream/master'
RobynCastro Mar 2, 2019
741e587
Fxied conflicts
RobynCastro Mar 2, 2019
32567f9
Fixed formatting
RobynCastro Mar 9, 2019
21115d6
Merge remote-tracking branch 'upstream/master' into robyn/risk-analysis
RobynCastro Mar 9, 2019
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
Prev Previous commit
Next Next commit
Added better tests for region initialisation
  • Loading branch information
RobynCastro committed Feb 23, 2019
commit fc24b5c472945f0d44ca53305ccf20b634618412
193 changes: 122 additions & 71 deletions src/sb_pointcloud_processing/test/risk-analysis-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,60 +10,57 @@
#include <RiskAnalysis.h>
#include <gtest/gtest.h>

/*
* Function Prototype for Risk Analysis
*
* RiskAnalysis(float region_width, float region_height, int
* num_vertical_cell_div,
* int num_horizontal_cell_div, int region_min_points);
pcl::PCLPointCloud2 empty_cloud = pcl::PCLPointCloud2();

/**
* Runs tests to verify the inputted point_region has the proper dimensions specified
* by all the other inputs
*
* @param point_region
* @param region_width
* @param region_height
* @param num_vertical_cell_divs
* @param num_horizontal_cell_divs
*/

pcl::PCLPointCloud2 empty_cloud = pcl::PCLPointCloud2();
void testRegionDimensions(std::vector<std::vector<RegionOfPoints>> point_region,
float region_width,
float region_height,
int num_vertical_cell_divs,
int num_horizontal_cell_divs);

TEST(RegionCreation, DivisionsEqualToDimensions) {
float region_width = 10;
float region_height = 10;
int num_vertical_cell_divs = 10;
int num_horizontal_cell_divs = 10;
int min_points_in_region = 1;
float risk_multiplier = 1;
RiskAnalysis risk_analysis = RiskAnalysis(region_width,
region_height,
num_vertical_cell_divs,
num_horizontal_cell_divs,
min_points_in_region,
risk_multiplier);

sb_geom_msgs::Polygon2D top_left_region =
risk_analysis.getRegionAreaFromIndices(0, 0);
EXPECT_FLOAT_EQ(region_height, top_left_region.points[0].x);
EXPECT_FLOAT_EQ(region_width / 2, top_left_region.points[0].y);

sb_geom_msgs::Polygon2D top_right_region =
risk_analysis.getRegionAreaFromIndices(0, 9);
EXPECT_FLOAT_EQ(region_height, top_right_region.points[1].x);
EXPECT_FLOAT_EQ(-region_width / 2, top_right_region.points[1].y);

sb_geom_msgs::Polygon2D bottom_right_region =
risk_analysis.getRegionAreaFromIndices(9, 9);
EXPECT_FLOAT_EQ(0, bottom_right_region.points[2].x);
EXPECT_FLOAT_EQ(-region_width / 2, bottom_right_region.points[2].y);

sb_geom_msgs::Polygon2D bottom_left_region =
risk_analysis.getRegionAreaFromIndices(9, 0);
EXPECT_FLOAT_EQ(0, bottom_left_region.points[3].x);
EXPECT_FLOAT_EQ(region_width / 2, bottom_left_region.points[3].y);

sb_geom_msgs::Polygon2D test_region =
risk_analysis.getRegionAreaFromIndices(2, 9);
/**
*
* @param risk_analysis
* @param region_width
* @param region_height
* @param num_vertical_cell_divs
* @param num_horizontal_cell_divs
*/
void testRegionLocations(RiskAnalysis risk_analysis,
float region_width,
float region_height,
int num_vertical_cell_divs,
int num_horizontal_cell_divs);
/**
* Runs tests to determine equality of points
*/
void EXPECT_POINT_EQ(sb_geom_msgs::Point2D expected_val, sb_geom_msgs::Point2D actual_val) {
float abs_error = 0.0001;

std::cout << risk_analysis.determineColumn(-4.5) << std::endl;
EXPECT_NEAR(expected_val.x, actual_val.x, abs_error);
EXPECT_NEAR(expected_val.y, actual_val.y, abs_error);
}

/**
* Creates a point with specified values
*/
sb_geom_msgs::Point2D createPoint(float x, float y) {
sb_geom_msgs::Point2D point;
point.x = x;
point.y = y;

return point;
}

TEST(RegionInitialisation, DivisionsEqualToDimensions) {
Expand Down Expand Up @@ -92,6 +89,8 @@ TEST(RegionInitialisation, DivisionsEqualToDimensions) {
region_height,
num_vertical_cell_divs,
num_horizontal_cell_divs);

testRegionLocations(risk_analysis, region_width, region_height, num_vertical_cell_divs, num_horizontal_cell_divs);
}

TEST(RegionAnalysis, DivisionsEqualToDimensions) {
Expand All @@ -113,7 +112,7 @@ TEST(RegionAnalysis, DivisionsEqualToDimensions) {
risk_analysis.assessPointCloudRisk(empty_cloud);
}

TEST(RegionCreation, NonIntegerCellDimensions) {
TEST(RegionInitialisation, NonIntegerCellDimensions) {
float region_width = 10;
float region_height = 10;
int num_vertical_cell_divs = 100;
Expand All @@ -128,28 +127,20 @@ TEST(RegionCreation, NonIntegerCellDimensions) {
min_points_in_region,
risk_multiplier);

sb_geom_msgs::Polygon2D top_left_region =
risk_analysis.getRegionAreaFromIndices(0, 0);
EXPECT_FLOAT_EQ(region_height, top_left_region.points[0].x);
EXPECT_FLOAT_EQ(region_width / 2, top_left_region.points[0].y);
std::vector<std::vector<RegionOfPoints>> point_region;

sb_geom_msgs::Polygon2D top_right_region =
risk_analysis.getRegionAreaFromIndices(0, 99);
EXPECT_FLOAT_EQ(region_height, top_right_region.points[1].x);
EXPECT_FLOAT_EQ(-region_width / 2, top_right_region.points[1].y);
point_region = risk_analysis.initialisePointRegions();

sb_geom_msgs::Polygon2D bottom_right_region =
risk_analysis.getRegionAreaFromIndices(99, 99);
EXPECT_NEAR(0, bottom_right_region.points[2].x, 0.001);
EXPECT_FLOAT_EQ(-region_width / 2, bottom_right_region.points[2].y);
EXPECT_EQ(num_vertical_cell_divs, point_region.size());
EXPECT_EQ(num_horizontal_cell_divs, point_region[0].size());

sb_geom_msgs::Polygon2D bottom_left_region =
risk_analysis.getRegionAreaFromIndices(99, 0);
EXPECT_FLOAT_EQ(0, bottom_left_region.points[3].x);
EXPECT_FLOAT_EQ(region_width / 2, bottom_left_region.points[3].y);
testRegionDimensions(point_region,
region_width,
region_height,
num_vertical_cell_divs,
num_horizontal_cell_divs);

int row = risk_analysis.determineRow(2.8);
int col = risk_analysis.determineColumn(0);
testRegionLocations(risk_analysis, region_width, region_height, num_vertical_cell_divs, num_horizontal_cell_divs);

}

Expand All @@ -172,6 +163,37 @@ TEST(RegionAnalysis, NonIntegerCellDimensions) {
risk_analysis.assessPointCloudRisk(empty_cloud);
}

TEST(RegionInitialisation, OneDiv) {
float region_width = 2;
float region_height = 2;
int num_vertical_cell_divs = 2;
int num_horizontal_cell_divs = 1;
int min_points_in_region = -1;
float risk_multiplier = 1;

RiskAnalysis risk_analysis = RiskAnalysis(region_width,
region_height,
num_vertical_cell_divs,
num_horizontal_cell_divs,
min_points_in_region,
risk_multiplier);

std::vector<std::vector<RegionOfPoints>> point_region;

point_region = risk_analysis.initialisePointRegions();

EXPECT_EQ(num_vertical_cell_divs, point_region.size());
EXPECT_EQ(num_horizontal_cell_divs, point_region[0].size());

testRegionDimensions(point_region,
region_width,
region_height,
num_vertical_cell_divs,
num_horizontal_cell_divs);

testRegionLocations(risk_analysis, region_width, region_height, num_vertical_cell_divs, num_horizontal_cell_divs);
}

TEST(RegionAnalysis, OneDiv) {
float region_width = 2;
float region_height = 2;
Expand Down Expand Up @@ -199,29 +221,58 @@ void testRegionDimensions(std::vector<std::vector<RegionOfPoints>> point_region,
float cell_width = region_width / num_horizontal_cell_divs;
float cell_height = region_height / num_vertical_cell_divs;

float abs_error = 0.001;
for (int i = 0; i < point_region.size(); i++) {
for (int j = 0; j < point_region[0].size(); j++) {
sb_geom_msgs::Polygon2D cur_cell = point_region[i][j].region_area;

// Top Left Point vs Bottom Left Point
EXPECT_FLOAT_EQ(cell_height,
cur_cell.points[0].x - cur_cell.points[3].x);
EXPECT_NEAR(cell_height, cur_cell.points[0].x - cur_cell.points[3].x, abs_error);

// Top Right Point vs Bottom Right Point
EXPECT_FLOAT_EQ(cell_height,
cur_cell.points[1].x - cur_cell.points[2].x);
EXPECT_NEAR(cell_height, cur_cell.points[1].x - cur_cell.points[2].x, abs_error);

// Top Left Point vs Top Right Point
EXPECT_FLOAT_EQ(cell_width,
cur_cell.points[0].y - cur_cell.points[1].y);
EXPECT_NEAR(cell_width, cur_cell.points[0].y - cur_cell.points[1].y, abs_error);

// Bottom Left Point vs Bottom Right Point
EXPECT_FLOAT_EQ(cell_width,
cur_cell.points[3].y - cur_cell.points[2].y);
EXPECT_NEAR(cell_width, cur_cell.points[3].y - cur_cell.points[2].y, abs_error);
}
}
}

void testRegionLocations(RiskAnalysis risk_analysis,
float region_width,
float region_height,
int num_vertical_cell_divs,
int num_horizontal_cell_divs) {
float cell_width = region_width / num_horizontal_cell_divs;
float cell_height = region_height / num_vertical_cell_divs;

float cur_cell_top = region_height;
for (int i = 0; i < num_vertical_cell_divs; i++) {
float cur_cell_left = region_width / 2;

for (int j = 0; j < num_horizontal_cell_divs; j++) {
sb_geom_msgs::Polygon2D cur_region =
risk_analysis.getRegionAreaFromIndices(i, j);

sb_geom_msgs::Point2D top_left_point = createPoint(cur_cell_top, cur_cell_left);
sb_geom_msgs::Point2D top_right_point = createPoint(cur_cell_top, cur_cell_left - cell_width);
sb_geom_msgs::Point2D bottom_right_point = createPoint(cur_cell_top - cell_height, cur_cell_left - cell_width);
sb_geom_msgs::Point2D bottom_left_point = createPoint(cur_cell_top - cell_height, cur_cell_left);

EXPECT_POINT_EQ(top_left_point, cur_region.points[0]);
EXPECT_POINT_EQ(top_right_point, cur_region.points[1]);
EXPECT_POINT_EQ(bottom_right_point, cur_region.points[2]);
EXPECT_POINT_EQ(bottom_left_point, cur_region.points[3]);
cur_cell_left -= cell_width;
}

cur_cell_top -= cell_height;
}
}

TEST(StandardDeviation, OneDataPoint) {
RiskAnalysis risk_analysis = RiskAnalysis();

Expand Down