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

feature/test_object_sanitizer #1713

Merged
merged 3 commits into from
Nov 14, 2018
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
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,11 @@ catkin_package(
tf
)

include_directories(
include
${catkin_INCLUDE_DIRS}
)

#lib
add_library(roi_object_filter_lib SHARED
src/roi_object_filter.cpp
Expand Down Expand Up @@ -98,3 +103,9 @@ install(TARGETS roi_object_filter
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
PATTERN ".svn" EXCLUDE)

if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest_gtest(test-roi_object_filter test/test_roi_object_filter.test test/src/test_roi_object_filter.cpp)
target_link_libraries(test-roi_object_filter ${catkin_LIBRARIES} roi_object_filter_lib)
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@

class RosRoiObjectFilterApp
{
friend class TestClass;
ros::NodeHandle node_handle_;

ros::Subscriber detections_range_subscriber_, wayarea_gridmap_subscriber_;
Expand Down Expand Up @@ -114,7 +115,6 @@ class RosRoiObjectFilterApp
tf::StampedTransform FindTransform(const std::string& in_target_frame, const std::string& in_source_frame);
geometry_msgs::Point TransformPoint(const geometry_msgs::Point& in_point, const tf::Transform& in_tf);


public:
void Run();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -278,4 +278,4 @@ RosRoiObjectFilterApp::RosRoiObjectFilterApp()
gridmap_ready_ = false;
detections_ready_ = false;
processing_ = false;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
#include <ros/ros.h>
#include <gtest/gtest.h>

#include "roi_object_filter/roi_object_filter.h"

class TestSuite: public ::testing::Test {
public:
TestSuite(){}
~TestSuite(){}
};

class TestClass{
public:
TestClass(){};

RosRoiObjectFilterApp app;

geometry_msgs::Point TransformPoint(const geometry_msgs::Point& in_point, const tf::Transform& in_tf);
bool CheckPointInGrid(const grid_map::GridMap& in_grid_map, const cv::Mat& in_grid_image,
const geometry_msgs::Point& in_point);
};

geometry_msgs::Point TestClass::TransformPoint(const geometry_msgs::Point& in_point, const tf::Transform& in_tf)
{
return app.TransformPoint(in_point, in_tf);
}

bool TestClass::CheckPointInGrid(const grid_map::GridMap& in_grid_map, const cv::Mat& in_grid_image,
const geometry_msgs::Point& in_point)
{
return app.CheckPointInGrid(in_grid_map, in_grid_image, in_point);
}


TEST(TestSuite, CheckTransformPoint){

TestClass testObj;

// Check translation of 1 along X axis
tf::Quaternion q(0,0,0,1);
tf::Vector3 v(1,0,0);
geometry_msgs::Point inPt, outPt, expectedPt;

inPt.x = 0;
inPt.y = 0;
inPt.z = 0;
expectedPt.x = 1;
expectedPt.y = 0;
expectedPt.z = 0;

tf::Transform translation(q, v);

outPt = testObj.TransformPoint(inPt, translation);

ASSERT_EQ(outPt.x, expectedPt.x) << "X Coordinate should be " << expectedPt.x;
ASSERT_EQ(outPt.y, expectedPt.y) << "Y Coordinate should be " << expectedPt.y;
ASSERT_EQ(outPt.z, expectedPt.z) << "Z Coordinate should be " << expectedPt.z;

}



int main(int argc, char **argv) {
testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "TestNode");
return RUN_ALL_TESTS();
}

Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<launch>

<test test-name="test-roi_object_filter" pkg="roi_object_filter" type="test-roi_object_filter" name="test"/>

</launch>