trajectory_files_manager_test.cpp
Go to the documentation of this file.
2 #include <ros/package.h>
3 #include <ros/ros.h>
4 
5 #include <gtest/gtest.h>
6 
7 TEST(TestSuite, testWriteYamlFile)
8 {
9  //make poly_data
10  vtkSmartPointer<vtkPolyData> poly_data = vtkSmartPointer<vtkPolyData>::New();
11  vtkSmartPointer<vtkPolyData> poly_data_2 = vtkSmartPointer<vtkPolyData>::New();
12 
13  vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New();
14  vtkSmartPointer<vtkCellArray> polygon_array = vtkSmartPointer<vtkCellArray>::New();
15 
16  // First contour
17  vtkSmartPointer<vtkPolygon> polygon = vtkSmartPointer<vtkPolygon>::New();
18  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
19  points->InsertNextPoint(0, 0, 0);
20  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
21  points->InsertNextPoint(0, 2, 0);
22  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
23  points->InsertNextPoint(2, 2, 0);
24  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
25  points->InsertNextPoint(2, 0, 0);
26 
27  polygon_array->InsertNextCell(polygon);
28  // Second contour
29  polygon = vtkSmartPointer<vtkPolygon>::New();
30  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
31  points->InsertNextPoint(10, 10, 0);
32  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
33  points->InsertNextPoint(11, 11, 0);
34  polygon->GetPointIds()->InsertNextId(points->GetNumberOfPoints());
35  points->InsertNextPoint(12, 10, 0);
36 
37  polygon_array->InsertNextCell(polygon);
38 
39  poly_data->SetPoints(points);
40  poly_data->SetPolys(polygon_array);
41 
42  const std::string yaml_file(ros::package::getPath("ram_utils") + "/test/testWriteYamlFile.yaml");
43  // std::string yaml_file = "testWriteYamlFile.yaml";
44  EXPECT_TRUE(ram_utils::polydataToYamlFile(yaml_file, poly_data));
45 }
46 
47 TEST(TestSuite, testReadEmptyPolydata)
48 {
49  //make poly_data
50  vtkSmartPointer<vtkPolyData> poly_data = vtkSmartPointer<vtkPolyData>::New();
51  const std::string yaml_file(ros::package::getPath("ram_utils") + "/test/testWriteYamlFile2.yaml");
52  EXPECT_FALSE(ram_utils::polydataToYamlFile(yaml_file, poly_data));
53 }
54 
55 TEST(TestSuite, testReadYamlFile)
56 {
57  //make poly_data
58  vtkSmartPointer<vtkPolyData> poly_data = vtkSmartPointer<vtkPolyData>::New();
59 
60  const std::string yaml_file(ros::package::getPath("ram_utils") + "/test/testReadYamlFile.yaml");
61  bool result = ram_utils::yamlFileToPolydata(yaml_file, poly_data);
62  bool is_empty = (poly_data->GetNumberOfCells() == 0) ? true : false;
63  EXPECT_TRUE(result && !is_empty);
64 }
65 
66 TEST(TestSuite, testReadEmptyYamlFile)
67 {
68  //make poly_data
69  vtkSmartPointer<vtkPolyData> poly_data = vtkSmartPointer<vtkPolyData>::New();
70 
71  const std::string yaml_file(
72  ros::package::getPath("ram_utils") + "/test/testReadEmptyYamlFile.yaml");
73  bool result = ram_utils::yamlFileToPolydata(yaml_file, poly_data);
74  bool is_empty = (poly_data->GetNumberOfCells() == 0) ? true : false;
75  EXPECT_FALSE(result && !is_empty);
76 }
77 
78 int main(int argc,
79  char **argv)
80 {
81  ros::init(argc, argv, "trajectory_files_manager_test");
82  testing::InitGoogleTest(&argc, argv);
83  return RUN_ALL_TESTS();
84 }
bool yamlFileToPolydata(const std::string yaml_file, Polygon poly_data)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
bool polydataToYamlFile(const std::string yaml_file, const Polygon poly_data)
ROSLIB_DECL std::string getPath(const std::string &package_name)
TEST(TestSuite, testWriteYamlFile)


ram_utils
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 14:49:54