31
31
32
32
#include < string>
33
33
34
+ #include < opencv2/imgcodecs.hpp>
35
+
34
36
#include < sensor_msgs/msg/point_cloud2.hpp>
35
- #include < sensor_msgs/point_cloud_iterator .hpp>
37
+ #include < sensor_msgs/point_cloud2_iterator .hpp>
36
38
37
39
#include < projected_point_cloud_transport/projected_publisher.hpp>
38
40
@@ -61,11 +63,11 @@ ProjectedPublisher::TypedEncodeResult ProjectedPublisher::encodeTyped(
61
63
case (point_cloud_interfaces::msg::ProjectedPointCloud::SPHERICAL_PROJECTION):
62
64
projectCloudOntoSphere (raw, projected_pointcloud_image);
63
65
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!" );
65
67
}
66
68
67
69
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!" );
69
71
return cras::make_unexpected (" Failed to project pointcloud onto image!" );
70
72
}
71
73
@@ -86,10 +88,10 @@ ProjectedPublisher::TypedEncodeResult ProjectedPublisher::encodeTyped(
86
88
return compressed;
87
89
}
88
90
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 {
90
92
if (cloud.is_dense ){
91
93
// 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 () );
93
95
}else {
94
96
// TODO ([email protected] ): Make these parameters
95
97
const int view_height = 720 ;
@@ -99,11 +101,18 @@ void ProjectedPublisher::projectCloudOntoPlane(const sensor_msgs::msg::PointClou
99
101
const float ppy = view_height/2 ;
100
102
const float fx = view_width;
101
103
const float fy = view_width;
104
+
102
105
// 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
+
103
112
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 ;
107
116
108
117
if (!std::isfinite (x) || !std::isfinite (y) || !std::isfinite (z)){
109
118
continue ;
@@ -112,60 +121,61 @@ void ProjectedPublisher::projectCloudOntoPlane(const sensor_msgs::msg::PointClou
112
121
// TODO (john-maidbot): rotate the d x/y/z so that z is along the view point orientation
113
122
// TODO: can that be made more efficient by transforming the view point instead?
114
123
115
- if (z == 0 ){
116
- continue ;
117
- }
118
-
119
124
const int col = x/z * fx + ppx;
120
125
const int row = y/z * fy + ppy;
121
126
127
+ if (z == 0 || col < 0 || row < 0 || col >= view_width || row >= view_height){
128
+ continue ;
129
+ }
130
+
122
131
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
124
133
}
125
-
126
134
}
127
135
}
128
136
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 {
130
138
// 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
133
141
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 ;
135
143
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 )};
141
145
142
146
// 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" );
146
150
147
151
for (; iter_x != iter_x.end (); ++iter_x, ++iter_y, ++iter_z) {
148
152
// TODO ([email protected] ): should spherical projection account
149
153
// 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 ;
153
157
154
158
if (!std::isfinite (x) || !std::isfinite (y) || !std::isfinite (z)){
155
159
continue ;
156
160
}
157
161
158
162
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
+ }
161
171
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) ;
164
174
165
- auto & cell = spherical_image_ .at <uint16_t >(phi_index, rho_index );
175
+ auto & cell = spherical_image .at <uint16_t >(phi_index, theta_index );
166
176
cell = std::min (cell, static_cast <uint16_t >(rho * 1000 )); // mm resolution
167
177
}
168
- projected_pointcloud_image = spherical_image_ ;
178
+ projected_pointcloud_image = spherical_image ;
169
179
}
170
180
171
181
} // namespace projected_point_cloud_transport
0 commit comments