Skip to content

Commit 6108034

Browse files
committed
Builds
1 parent 0d21936 commit 6108034

File tree

9 files changed

+140
-79
lines changed

9 files changed

+140
-79
lines changed

point_cloud_interfaces/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,17 +3,19 @@ project(point_cloud_interfaces)
33

44
find_package(ament_cmake REQUIRED)
55
find_package(builtin_interfaces REQUIRED)
6+
find_package(geometry_msgs REQUIRED)
67
find_package(rosidl_default_generators REQUIRED)
78
find_package(sensor_msgs REQUIRED)
89
find_package(std_msgs REQUIRED)
910

1011
set(msg_files
1112
"msg/CompressedPointCloud2.msg"
13+
"msg/ProjectedPointCloud.msg"
1214
)
1315

1416
rosidl_generate_interfaces(${PROJECT_NAME}
1517
${msg_files}
16-
DEPENDENCIES sensor_msgs std_msgs builtin_interfaces
18+
DEPENDENCIES geometry_msgs sensor_msgs std_msgs builtin_interfaces
1719
)
1820

1921
if(BUILD_TESTING)

point_cloud_interfaces/msg/ProjectedPointCloud.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ bool was_dense
1717
uint8[] compressed_data
1818

1919
# This is the point/orientation that acts as a reference for the pointcloud compression
20-
geometry_msgs/Pose view_point;
20+
geometry_msgs/Pose view_point
2121

2222
# TODO: How to maintain fields data?
2323
# sensor_msgs/PointField[] fields

point_cloud_interfaces/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
<build_depend>builtin_interfaces</build_depend>
1717
<buildtool_depend>rosidl_default_generators</buildtool_depend>
1818

19+
<depend>geometry_msgs</depend>
1920
<depend>sensor_msgs</depend>
2021
<depend>std_msgs</depend>
2122

projected_point_cloud_transport/CMakeLists.txt

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,27 +5,33 @@ set(CMAKE_CXX_STANDARD 17)
55
project(projected_point_cloud_transport)
66

77
find_package(ament_cmake REQUIRED)
8+
find_package(OpenCV REQUIRED)
89
find_package(pluginlib REQUIRED)
910
find_package(point_cloud_interfaces REQUIRED)
1011
find_package(point_cloud_transport REQUIRED)
1112
find_package(rclcpp REQUIRED)
13+
find_package(sensor_msgs REQUIRED)
1214

1315
set(dependencies
16+
OpenCV
1417
pluginlib
1518
point_cloud_interfaces
1619
point_cloud_transport
1720
rclcpp
21+
sensor_msgs
1822
)
1923

2024

21-
include_directories(include)
25+
include_directories(
26+
include
27+
${OpenCV_INCLUDE_DIRS}
28+
)
2229

2330
add_library(${PROJECT_NAME}
2431
SHARED
32+
src/manifest.cpp
2533
src/projected_publisher.cpp
2634
src/projected_subscriber.cpp
27-
src/projected_cpp.cpp
28-
src/manifest.cpp
2935
)
3036

3137
ament_target_dependencies(${PROJECT_NAME} ${dependencies})

projected_point_cloud_transport/include/projected_point_cloud_transport/projected_publisher.hpp

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -35,13 +35,14 @@
3535
#include <memory>
3636
#include <string>
3737

38+
#include <opencv2/core.hpp>
39+
40+
#include <geometry_msgs/msg/pose.hpp>
3841
#include <sensor_msgs/msg/point_cloud2.hpp>
3942

40-
#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>
43+
#include <point_cloud_interfaces/msg/projected_point_cloud.hpp>
4144
#include <point_cloud_transport/point_cloud_transport.hpp>
42-
4345
#include <point_cloud_transport/simple_publisher_plugin.hpp>
44-
#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>
4546

4647

4748
namespace projected_point_cloud_transport
@@ -58,14 +59,20 @@ class ProjectedPublisher
5859

5960
TypedEncodeResult encodeTyped(const sensor_msgs::msg::PointCloud2 & raw) const override;
6061

62+
std::string getDataType() const override
63+
{
64+
return "point_cloud_interfaces/msg/ProjectedPointCloud";
65+
}
66+
6167
private:
6268

63-
geoemtry_msgs::msg::Pose view_point_;
69+
void projectCloudOntoPlane(const sensor_msgs::msg::PointCloud2& cloud, cv::Mat& projected_pointcloud_image) const;
70+
71+
void projectCloudOntoSphere(const sensor_msgs::msg::PointCloud2& cloud, cv::Mat& projected_pointcloud_image) const;
6472

65-
// Optimization: If the user has spherical projection turned on, we never need to reallocate the
66-
// spherical_projection_ image as its dimensions are not influenced by the pointcloud size.
67-
cv::Mat spherical_projection_;
73+
uint8_t projection_type_;
6874

75+
geometry_msgs::msg::Pose view_point_;
6976

7077
};
7178
} // namespace projected_point_cloud_transport

projected_point_cloud_transport/include/projected_point_cloud_transport/projected_subscriber.hpp

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,13 @@
3333
#define PROJECTED_POINT_CLOUD_TRANSPORT__PROJECTED_SUBSCRIBER_HPP_
3434

3535
#include <string>
36+
#include <vector>
3637

37-
#include <point_cloud_interfaces/msg/compressed_point_cloud2.hpp>
38+
#include <opencv2/core.hpp>
3839

40+
#include <sensor_msgs/msg/point_cloud2.hpp>
41+
42+
#include <point_cloud_interfaces/msg/projected_point_cloud.hpp>
3943
#include <point_cloud_transport/simple_subscriber_plugin.hpp>
4044
#include <point_cloud_transport/transport_hints.hpp>
4145

@@ -53,6 +57,18 @@ class ProjectedSubscriber
5357

5458
DecodeResult decodeTyped(const point_cloud_interfaces::msg::ProjectedPointCloud & compressed)
5559
const override;
60+
61+
std::string getDataType() const override
62+
{
63+
return "point_cloud_interfaces/msg/ProjectedPointCloud";
64+
}
65+
66+
private:
67+
68+
void deprojectSphereToCloud(const cv::Mat& projected_pointcloud_image, const point_cloud_interfaces::msg::ProjectedPointCloud& msg, sensor_msgs::msg::PointCloud2::SharedPtr& cloud) const;
69+
70+
void deprojectPlaneToCloud(const cv::Mat& projected_pointcloud_image, const point_cloud_interfaces::msg::ProjectedPointCloud& msg, sensor_msgs::msg::PointCloud2::SharedPtr& cloud) const;
71+
5672
};
5773
} // namespace projected_point_cloud_transport
5874

projected_point_cloud_transport/package.xml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,11 @@
2020

2121
<exec_depend>pluginlib</exec_depend>
2222

23+
<depend>OpenCV</depend>
2324
<depend>point_cloud_interfaces</depend>
2425
<depend>point_cloud_transport</depend>
2526
<depend>rclcpp</depend>
26-
<depend>libopencv</depend>
27+
<depend>sensor_msgs</depend>
2728

2829
<test_depend>ament_lint_auto</test_depend>
2930
<test_depend>ament_lint_common</test_depend>

projected_point_cloud_transport/src/projected_publisher.cpp

Lines changed: 45 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,10 @@
3131

3232
#include <string>
3333

34+
#include <opencv2/imgcodecs.hpp>
35+
3436
#include <sensor_msgs/msg/point_cloud2.hpp>
35-
#include <sensor_msgs/point_cloud_iterator.hpp>
37+
#include <sensor_msgs/point_cloud2_iterator.hpp>
3638

3739
#include <projected_point_cloud_transport/projected_publisher.hpp>
3840

@@ -61,11 +63,11 @@ ProjectedPublisher::TypedEncodeResult ProjectedPublisher::encodeTyped(
6163
case(point_cloud_interfaces::msg::ProjectedPointCloud::SPHERICAL_PROJECTION):
6264
projectCloudOntoSphere(raw, projected_pointcloud_image);
6365
default:
64-
RCLCPP_ERROR(getLogger(), "Projection type " << projection_type_ << " is not known/supported!");
66+
RCLCPP_ERROR_STREAM(getLogger(), "Projection type " << projection_type_ << " is not known/supported!");
6567
}
6668

6769
if(projected_pointcloud_image.empty()){
68-
RCLCPP_ERROR(getLogger(), "Projection type " << projection_type_ << " failed to project pointcloud!");
70+
RCLCPP_ERROR_STREAM(getLogger(), "Projection type " << projection_type_ << " failed to project pointcloud!");
6971
return cras::make_unexpected("Failed to project pointcloud onto image!");
7072
}
7173

@@ -86,10 +88,10 @@ ProjectedPublisher::TypedEncodeResult ProjectedPublisher::encodeTyped(
8688
return compressed;
8789
}
8890

89-
void ProjectedPublisher::projectCloudOntoPlane(const sensor_msgs::msg::PointCloud2& cloud, cv::Mat& projected_pointcloud_image){
91+
void ProjectedPublisher::projectCloudOntoPlane(const sensor_msgs::msg::PointCloud2& cloud, cv::Mat& projected_pointcloud_image) const{
9092
if(cloud.is_dense){
9193
// TODO ([email protected]): if the pointcloud is already organized, just point the cv::Mat at the data
92-
projected_pointcloud_image = cv::Mat(cv::Size(cloud.width, cloud.height), CV_16UC1, cloud.data);
94+
projected_pointcloud_image = cv::Mat((int)cloud.height, (int)cloud.width, CV_32FC3, (void*)cloud.data.data());
9395
}else{
9496
// TODO ([email protected]): Make these parameters
9597
const int view_height = 720;
@@ -99,11 +101,18 @@ void ProjectedPublisher::projectCloudOntoPlane(const sensor_msgs::msg::PointClou
99101
const float ppy = view_height/2;
100102
const float fx = view_width;
101103
const float fy = view_width;
104+
102105
// if the pointcloud is NOT already organized, we need to apply the projection
106+
107+
// iterate over the pointcloud
108+
sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
109+
sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
110+
sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
111+
103112
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
104-
const double& x = *iter_x - view_point.position.x;
105-
const double& y = *iter_y - view_point.position.y;
106-
const double& z = *iter_z - view_point.position.z;
113+
const double& x = *iter_x - view_point_.position.x;
114+
const double& y = *iter_y - view_point_.position.y;
115+
const double& z = *iter_z - view_point_.position.z;
107116

108117
if(!std::isfinite(x) || !std::isfinite(y) || !std::isfinite(z)){
109118
continue;
@@ -112,60 +121,61 @@ void ProjectedPublisher::projectCloudOntoPlane(const sensor_msgs::msg::PointClou
112121
// TODO (john-maidbot): rotate the d x/y/z so that z is along the view point orientation
113122
// TODO: can that be made more efficient by transforming the view point instead?
114123

115-
if(z == 0){
116-
continue;
117-
}
118-
119124
const int col = x/z * fx + ppx;
120125
const int row = y/z * fy + ppy;
121126

127+
if(z == 0 || col < 0 || row < 0 || col >= view_width || row >= view_height){
128+
continue;
129+
}
130+
122131
auto& cell = projected_pointcloud_image.at<uint16_t>(row, col);
123-
cell = std::min(cell, static_cast<uint16_t>(depth * 1000)); // mm resolution
132+
cell = std::min(cell, static_cast<uint16_t>(z * 1000)); // mm resolution
124133
}
125-
126134
}
127135
}
128136

129-
void ProjectedPublisher::projectCloudOntoSphere(const sensor_msgs::msg::PointCloud2& cloud, cv::Mat& projected_pointcloud_image){
137+
void ProjectedPublisher::projectCloudOntoSphere(const sensor_msgs::msg::PointCloud2& cloud, cv::Mat& projected_pointcloud_image) const{
130138
// TODO ([email protected]): Make these parameters
131-
const double phi_resolution = 0.5; // radians
132-
const double theta_resolution = 0.5; // radians
139+
const double phi_resolution = 0.034; // radians
140+
const double theta_resolution = 0.034; // radians
133141
const int phi_bins = 2 * M_PI / phi_resolution;
134-
const int theta_bins = 2 * M_PI / rho_resolution;
142+
const int theta_bins = 2 * M_PI / theta_resolution;
135143

136-
if(spherical_image.empty()){
137-
spherical_image_ = cv::Mat{phi_bins, theta_bins, CV_16UC1, cv::Scalar(0)};
138-
}else{
139-
spherical_image.setTo(0);
140-
}
144+
cv::Mat spherical_image{phi_bins, theta_bins, CV_16UC1, cv::Scalar(0)};
141145

142146
// iterate over the pointcloud and convert to polar coordinates
143-
sensor_msgs::PointCloud2ConstIterator<float> iter_x(raw, "x");
144-
sensor_msgs::PointCloud2ConstIterator<float> iter_y(raw, "y");
145-
sensor_msgs::PointCloud2ConstIterator<float> iter_z(raw, "z");
147+
sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
148+
sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
149+
sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
146150

147151
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
148152
// TODO ([email protected]): should spherical projection account
149153
// for the orientation of the view point?
150-
const double& x = *iter_x - view_point.position.x;
151-
const double& y = *iter_y - view_point.position.y;
152-
const double& z = *iter_z - view_point.position.z;
154+
const double& x = *iter_x - view_point_.position.x;
155+
const double& y = *iter_y - view_point_.position.y;
156+
const double& z = *iter_z - view_point_.position.z;
153157

154158
if(!std::isfinite(x) || !std::isfinite(y) || !std::isfinite(z)){
155159
continue;
156160
}
157161

158162
const double rho = std::sqrt(x * x + y * y + z * z);
159-
const double phi = std::atan2(y, x);
160-
const double theta = std::acos(z / rho);
163+
double phi = std::atan2(y, x);
164+
double theta = std::acos(z / rho);
165+
if (phi < 0){
166+
phi += 2*M_PI;
167+
}
168+
if (theta < 0){
169+
theta += 2*M_PI;
170+
}
161171

162-
const int phi_index = phi / phi_resolution;
163-
const int theta_index = theta / theta_resolution;
172+
const int phi_index = std::min(static_cast<int>(phi / phi_resolution), phi_bins);
173+
const int theta_index = std::min(static_cast<int>(theta / theta_resolution), theta_bins);
164174

165-
auto& cell = spherical_image_.at<uint16_t>(phi_index, rho_index);
175+
auto& cell = spherical_image.at<uint16_t>(phi_index, theta_index);
166176
cell = std::min(cell, static_cast<uint16_t>(rho * 1000)); // mm resolution
167177
}
168-
projected_pointcloud_image = spherical_image_;
178+
projected_pointcloud_image = spherical_image;
169179
}
170180

171181
} // namespace projected_point_cloud_transport

0 commit comments

Comments
 (0)