helpers.cpp
Go to the documentation of this file.
1 /*
2  * helpers.cpp
3  *
4  * Created on: Nov 20, 2019
5  * Author: Edo Jelavic
6  * Institute: ETH Zurich, Robotic Systems Lab
7  */
8 
10 
13 
14 #include <cstdlib>
15 #include <memory>
16 
17 #include <pcl/common/common.h>
18 #include <pcl/common/transforms.h>
19 #include <pcl/conversions.h>
20 #include <pcl/io/pcd_io.h>
21 #include <pcl/point_types.h>
22 
23 #include <ros/console.h>
24 #include <ros/package.h>
25 
27 
28 namespace grid_map {
29 namespace grid_map_pcl {
30 
32  bool isSetVerbosityLevelToDebug;
33  nh.param<bool>("set_verbosity_to_debug", isSetVerbosityLevelToDebug, false);
34 
35  if (!isSetVerbosityLevelToDebug) {
36  return;
37  }
38 
41  }
42 }
43 
44 std::string getParameterPath() {
45  std::string filePath = ros::package::getPath("grid_map_pcl") + "/config/parameters.yaml";
46  return filePath;
47 }
48 
49 std::string getOutputBagPath(const ros::NodeHandle& nh) {
50  std::string outputRosbagName, folderPath;
51  nh.param<std::string>("folder_path", folderPath, "");
52  nh.param<std::string>("output_grid_map", outputRosbagName, "output_grid_map.bag");
53  std::string pathToOutputBag = folderPath + "/" + outputRosbagName;
54  return pathToOutputBag;
55 }
56 
57 std::string getPcdFilePath(const ros::NodeHandle& nh) {
58  std::string inputCloudName, folderPath;
59  nh.param<std::string>("folder_path", folderPath, "");
60  nh.param<std::string>("pcd_filename", inputCloudName, "input_cloud");
61  std::string pathToCloud = folderPath + "/" + inputCloudName;
62  return pathToCloud;
63 }
64 
65 std::string getMapFrame(const ros::NodeHandle& nh) {
66  std::string mapFrame;
67  nh.param<std::string>("map_frame", mapFrame, "map");
68  return mapFrame;
69 }
70 
71 std::string getMapRosbagTopic(const ros::NodeHandle& nh) {
72  std::string mapRosbagTopic;
73  nh.param<std::string>("map_rosbag_topic", mapRosbagTopic, "grid_map");
74  return mapRosbagTopic;
75 }
76 
77 std::string getMapLayerName(const ros::NodeHandle& nh) {
78  std::string mapLayerName;
79  nh.param<std::string>("map_layer_name", mapLayerName, "elevation");
80  return mapLayerName;
81 }
82 
83 void saveGridMap(const grid_map::GridMap& gridMap, const ros::NodeHandle& nh, const std::string& mapTopic) {
84  std::string pathToOutputBag = getOutputBagPath(nh);
85  const bool savingSuccessful = grid_map::GridMapRosConverter::saveToBag(gridMap, pathToOutputBag, mapTopic);
86  ROS_INFO_STREAM("Saving grid map successful: " << std::boolalpha << savingSuccessful);
87 }
88 
89 inline void printTimeElapsedToRosInfoStream(const std::chrono::system_clock::time_point& start, const std::string& prefix) {
90  const auto stop = std::chrono::high_resolution_clock::now();
91  const auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(stop - start).count() / 1000.0;
92  ROS_INFO_STREAM(prefix << duration << " sec");
93 }
94 
95 void processPointcloud(grid_map::GridMapPclLoader* gridMapPclLoader, const ros::NodeHandle& nh) {
96  const auto start = std::chrono::high_resolution_clock::now();
97  gridMapPclLoader->preProcessInputCloud();
98  gridMapPclLoader->initializeGridMapGeometryFromInputCloud();
99  printTimeElapsedToRosInfoStream(start, "Initialization took: ");
100  gridMapPclLoader->addLayerFromInputCloud(getMapLayerName(nh));
101  printTimeElapsedToRosInfoStream(start, "Total time: ");
102 }
103 
104 Eigen::Affine3f getRigidBodyTransform(const Eigen::Vector3d& translation, const Eigen::Vector3d& intrinsicRpy) {
105  Eigen::Affine3f rigidBodyTransform;
106  rigidBodyTransform.setIdentity();
107  rigidBodyTransform.translation() << translation.x(), translation.y(), translation.z();
108  Eigen::Matrix3f rotation(Eigen::Matrix3f::Identity());
109  rotation *= getRotationMatrix(intrinsicRpy.x(), XYZ::X);
110  rotation *= getRotationMatrix(intrinsicRpy.y(), XYZ::Y);
111  rotation *= getRotationMatrix(intrinsicRpy.z(), XYZ::Z);
112  rigidBodyTransform.rotate(rotation);
113 
114  return rigidBodyTransform;
115 }
116 
117 Eigen::Matrix3f getRotationMatrix(double angle, XYZ axis) {
118  Eigen::Matrix3f rotationMatrix = Eigen::Matrix3f::Identity();
119  switch (axis) {
120  case XYZ::X: {
121  rotationMatrix = Eigen::AngleAxisf(angle, Eigen::Vector3f::UnitX());
122  break;
123  }
124  case XYZ::Y: {
125  rotationMatrix = Eigen::AngleAxisf(angle, Eigen::Vector3f::UnitY());
126  break;
127  }
128  case XYZ::Z: {
129  rotationMatrix = Eigen::AngleAxisf(angle, Eigen::Vector3f::UnitZ());
130  break;
131  }
132  default:
133  ROS_ERROR("Unknown axis while trying to rotate the pointcloud");
134  }
135  return rotationMatrix;
136 }
137 
138 Eigen::Vector3d calculateMeanOfPointPositions(Pointcloud::ConstPtr inputCloud) {
139  Eigen::Vector3d mean = Eigen::Vector3d::Zero();
140  for (const auto& point : inputCloud->points) {
141  mean += Eigen::Vector3d(point.x, point.y, point.z);
142  }
143  mean /= inputCloud->points.size();
144 
145  return mean;
146 }
147 
148 Pointcloud::Ptr loadPointcloudFromPcd(const std::string& filename) {
149  Pointcloud::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
150  pcl::PCLPointCloud2 cloudBlob;
151  pcl::io::loadPCDFile(filename, cloudBlob);
152  pcl::fromPCLPointCloud2(cloudBlob, *cloud);
153  return cloud;
154 }
155 
156 Pointcloud::Ptr transformCloud(Pointcloud::ConstPtr inputCloud, const Eigen::Affine3f& transformMatrix) {
157  Pointcloud::Ptr transformedCloud(new Pointcloud());
158  pcl::transformPointCloud(*inputCloud, *transformedCloud, transformMatrix);
159  return transformedCloud;
160 }
161 
162 } /* namespace grid_map_pcl*/
163 } /* namespace grid_map */
void printTimeElapsedToRosInfoStream(const std::chrono::system_clock::time_point &start, const std::string &prefix)
Definition: helpers.cpp:89
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
std::string getPcdFilePath(const ros::NodeHandle &nh)
Definition: helpers.cpp:57
std::string getOutputBagPath(const ros::NodeHandle &nh)
Definition: helpers.cpp:49
Eigen::Matrix3f getRotationMatrix(double angle, XYZ axis)
Definition: helpers.cpp:117
Eigen::Vector3d calculateMeanOfPointPositions(Pointcloud::ConstPtr inputCloud)
Definition: helpers.cpp:138
static bool saveToBag(const grid_map::GridMap &gridMap, const std::string &pathToBag, const std::string &topic)
void addLayerFromInputCloud(const std::string &layer)
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void processPointcloud(grid_map::GridMapPclLoader *gridMapPclLoader, const ros::NodeHandle &nh)
Definition: helpers.cpp:95
Pointcloud::Ptr loadPointcloudFromPcd(const std::string &filename)
Definition: helpers.cpp:148
std::string getParameterPath()
Definition: helpers.cpp:44
std::string getMapLayerName(const ros::NodeHandle &nh)
Definition: helpers.cpp:77
ROSLIB_DECL std::string getPath(const std::string &package_name)
Pointcloud::Ptr transformCloud(Pointcloud::ConstPtr inputCloud, const Eigen::Affine3f &transformMatrix)
Definition: helpers.cpp:156
#define ROS_INFO_STREAM(args)
void setVerbosityLevelToDebugIfFlagSet(const ros::NodeHandle &nh)
Definition: helpers.cpp:31
void saveGridMap(const grid_map::GridMap &gridMap, const ros::NodeHandle &nh, const std::string &mapTopic)
Definition: helpers.cpp:83
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
::pcl::PointCloud< Point > Pointcloud
Definition: helpers.hpp:44
Eigen::Affine3f getRigidBodyTransform(const Eigen::Vector3d &translation, const Eigen::Vector3d &intrinsicRpy)
Definition: helpers.cpp:104
std::string getMapFrame(const ros::NodeHandle &nh)
Definition: helpers.cpp:65
#define ROS_ERROR(...)
#define ROSCONSOLE_DEFAULT_NAME
std::string getMapRosbagTopic(const ros::NodeHandle &nh)
Definition: helpers.cpp:71


grid_map_pcl
Author(s): Dominic Jud , Edo Jelavic
autogenerated on Tue Jun 1 2021 02:13:43