Skip to content

Commit 2b17a38

Browse files
doisygdoisyg
andauthored
build with openCV4 (#534)
* build with openCV4 * naive CI for foxy * deps * gtk3 * remove ibgtk2.0-dev * ament_uncrustify --reformat * test only image_pipeline packages Co-authored-by: doisyg <[email protected]>
1 parent 5ae707d commit 2b17a38

27 files changed

+147
-105
lines changed

.circleci/config.yml

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
version: 2
22
jobs:
3-
dashing:
3+
foxy:
44
docker:
5-
- image: ros:dashing-ros-base
5+
- image: jwhitleywork/ros:foxy-ros-base-focal
66
steps:
77
- checkout
88
- run:
@@ -13,8 +13,10 @@ jobs:
1313
apt upgrade -y
1414
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
1515
mkdir -p src/image_pipeline && mv `find -maxdepth 1 -not -name . -not -name src` src/image_pipeline/
16+
vcs import src \
17+
< src/image_pipeline/tools/ros2_dependencies.repos
1618
rosdep update
17-
rosdep install -y --from-paths . --ignore-src
19+
rosdep install -y --ignore-src --from-paths src
1820
- run:
1921
name: Build
2022
command: |
@@ -24,11 +26,11 @@ jobs:
2426
name: Run Tests
2527
command: |
2628
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
27-
colcon test --parallel-workers 1
29+
colcon test --packages-select camera_calibration depth_image_proc image_proc image_pipeline image_publisher image_rotate image_view stereo_image_proc --parallel-workers 1
2830
colcon test-result --verbose
2931
3032
workflows:
3133
version: 2
3234
ros_build:
3335
jobs:
34-
- dashing
36+
- foxy

depth_image_proc/src/convert_metric.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -88,9 +88,10 @@ void ConvertMetricNode::connectCb()
8888
sub_raw_.shutdown();
8989
} else if (!sub_raw_) {
9090
image_transport::TransportHints hints(this, "raw");
91-
sub_raw_ = image_transport::create_subscription(this, "image_raw",
92-
std::bind(&ConvertMetricNode::depthCb, this, std::placeholders::_1),
93-
hints.getTransport());
91+
sub_raw_ = image_transport::create_subscription(
92+
this, "image_raw",
93+
std::bind(&ConvertMetricNode::depthCb, this, std::placeholders::_1),
94+
hints.getTransport());
9495
}
9596
}
9697

depth_image_proc/src/crop_foremost.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -90,9 +90,10 @@ void CropForemostNode::connectCb()
9090
sub_raw_.shutdown();
9191
} else if (!sub_raw_) {
9292
image_transport::TransportHints hints(this, "raw");
93-
sub_raw_ = image_transport::create_subscription(this, "image_raw",
94-
std::bind(&CropForemostNode::depthCb, this, std::placeholders::_1),
95-
hints.getTransport());
93+
sub_raw_ = image_transport::create_subscription(
94+
this, "image_raw",
95+
std::bind(&CropForemostNode::depthCb, this, std::placeholders::_1),
96+
hints.getTransport());
9697
}
9798
}
9899

@@ -108,7 +109,8 @@ void CropForemostNode::depthCb(const sensor_msgs::msg::Image::ConstSharedPtr & r
108109

109110
// Check the number of channels
110111
if (sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1) {
111-
RCLCPP_ERROR(logger_, "Only grayscale image is acceptable, got [%s]",
112+
RCLCPP_ERROR(
113+
logger_, "Only grayscale image is acceptable, got [%s]",
112114
raw_msg->encoding.c_str());
113115
return;
114116
}

depth_image_proc/src/point_cloud_xyz_radial.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,8 @@ cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int heig
113113

114114
if (radial) {
115115
for (i = 0; i < totalsize; i++) {
116-
normalize(pixelVectors.at<cv::Vec3f>(i),
116+
normalize(
117+
pixelVectors.at<cv::Vec3f>(i),
117118
dst.at<cv::Vec3f>(i));
118119
}
119120
pixelVectors = dst;
@@ -156,8 +157,9 @@ void PointCloudXyzRadialNode::connectCb()
156157
sub_depth_ = image_transport::create_camera_subscription(
157158
this,
158159
"image_raw",
159-
std::bind(&PointCloudXyzRadialNode::depthCb, this, std::placeholders::_1,
160-
std::placeholders::_2),
160+
std::bind(
161+
&PointCloudXyzRadialNode::depthCb, this, std::placeholders::_1,
162+
std::placeholders::_2),
161163
"raw",
162164
custom_qos);
163165
}

depth_image_proc/src/point_cloud_xyzi.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -151,7 +151,8 @@ void PointCloudXyziNode::imageCb(
151151
{
152152
// Check for bad inputs
153153
if (depth_msg->header.frame_id != intensity_msg_in->header.frame_id) {
154-
RCLCPP_ERROR(logger_, "Depth image frame id [%s] doesn't match image frame id [%s]",
154+
RCLCPP_ERROR(
155+
logger_, "Depth image frame id [%s] doesn't match image frame id [%s]",
155156
depth_msg->header.frame_id.c_str(), intensity_msg_in->header.frame_id.c_str());
156157
return;
157158
}
@@ -186,7 +187,8 @@ void PointCloudXyziNode::imageCb(
186187
cv_bridge::CvImage cv_rsz;
187188
cv_rsz.header = cv_ptr->header;
188189
cv_rsz.encoding = cv_ptr->encoding;
189-
cv::resize(cv_ptr->image.rowRange(0, depth_msg->height / ratio), cv_rsz.image,
190+
cv::resize(
191+
cv_ptr->image.rowRange(0, depth_msg->height / ratio), cv_rsz.image,
190192
cv::Size(depth_msg->width, depth_msg->height));
191193
if ((intensity_msg->encoding == enc::MONO8) || (intensity_msg->encoding == enc::MONO16)) {
192194
intensity_msg = cv_rsz.toImageMsg();
@@ -206,7 +208,8 @@ void PointCloudXyziNode::imageCb(
206208
try {
207209
intensity_msg = cv_bridge::toCvCopy(intensity_msg, enc::MONO8)->toImageMsg();
208210
} catch (cv_bridge::Exception & e) {
209-
RCLCPP_ERROR(logger_, "Unsupported encoding [%s]: %s",
211+
RCLCPP_ERROR(
212+
logger_, "Unsupported encoding [%s]: %s",
210213
intensity_msg->encoding.c_str(), e.what());
211214
return;
212215
}
@@ -221,7 +224,8 @@ void PointCloudXyziNode::imageCb(
221224

222225
sensor_msgs::PointCloud2Modifier pcd_modifier(*cloud_msg);
223226
// pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "i");
224-
pcd_modifier.setPointCloud2Fields(4,
227+
pcd_modifier.setPointCloud2Fields(
228+
4,
225229
"x", 1, sensor_msgs::msg::PointField::FLOAT32,
226230
"y", 1, sensor_msgs::msg::PointField::FLOAT32,
227231
"z", 1, sensor_msgs::msg::PointField::FLOAT32,

depth_image_proc/src/point_cloud_xyzi_radial.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,8 @@ cv::Mat PointCloudXyziRadialNode::initMatrix(
141141

142142
if (radial) {
143143
for (i = 0; i < totalsize; i++) {
144-
normalize(pixelVectors.at<cv::Vec3f>(i),
144+
normalize(
145+
pixelVectors.at<cv::Vec3f>(i),
145146
dst.at<cv::Vec3f>(i));
146147
}
147148
pixelVectors = dst;
@@ -217,7 +218,8 @@ void PointCloudXyziRadialNode::imageCb(
217218
cloud_msg->is_bigendian = false;
218219

219220
sensor_msgs::PointCloud2Modifier pcd_modifier(*cloud_msg);
220-
pcd_modifier.setPointCloud2Fields(4,
221+
pcd_modifier.setPointCloud2Fields(
222+
4,
221223
"x", 1, sensor_msgs::msg::PointField::FLOAT32,
222224
"y", 1, sensor_msgs::msg::PointField::FLOAT32,
223225
"z", 1, sensor_msgs::msg::PointField::FLOAT32,
@@ -249,7 +251,8 @@ void PointCloudXyziRadialNode::imageCb(
249251
} else if (intensity_msg->encoding == enc::MONO8) {
250252
convert_intensity<uint8_t>(intensity_msg, cloud_msg);
251253
} else {
252-
RCLCPP_ERROR(logger_, "Intensity image has unsupported encoding [%s]",
254+
RCLCPP_ERROR(
255+
logger_, "Intensity image has unsupported encoding [%s]",
253256
intensity_msg->encoding.c_str());
254257
return;
255258
}

depth_image_proc/src/point_cloud_xyzrgb.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -168,7 +168,8 @@ void PointCloudXyzrgbNode::imageCb(
168168
{
169169
// Check for bad inputs
170170
if (depth_msg->header.frame_id != rgb_msg_in->header.frame_id) {
171-
RCLCPP_ERROR(logger_, "Depth image frame id [%s] doesn't match RGB image frame id [%s]",
171+
RCLCPP_ERROR(
172+
logger_, "Depth image frame id [%s] doesn't match RGB image frame id [%s]",
172173
depth_msg->header.frame_id.c_str(), rgb_msg_in->header.frame_id.c_str());
173174
return;
174175
}
@@ -203,7 +204,8 @@ void PointCloudXyzrgbNode::imageCb(
203204
cv_bridge::CvImage cv_rsz;
204205
cv_rsz.header = cv_ptr->header;
205206
cv_rsz.encoding = cv_ptr->encoding;
206-
cv::resize(cv_ptr->image.rowRange(0, depth_msg->height / ratio), cv_rsz.image,
207+
cv::resize(
208+
cv_ptr->image.rowRange(0, depth_msg->height / ratio), cv_rsz.image,
207209
cv::Size(depth_msg->width, depth_msg->height));
208210
if ((rgb_msg->encoding == enc::RGB8) || (rgb_msg->encoding == enc::BGR8) ||
209211
(rgb_msg->encoding == enc::MONO8))
@@ -213,7 +215,8 @@ void PointCloudXyzrgbNode::imageCb(
213215
rgb_msg = cv_bridge::toCvCopy(cv_rsz.toImageMsg(), enc::RGB8)->toImageMsg();
214216
}
215217

216-
RCLCPP_ERROR(logger_, "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)",
218+
RCLCPP_ERROR(
219+
logger_, "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)",
217220
depth_msg->width, depth_msg->height, rgb_msg->width, rgb_msg->height);
218221
return;
219222
} else {
@@ -261,10 +264,12 @@ void PointCloudXyzrgbNode::imageCb(
261264
pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
262265

263266
if (depth_msg->encoding == enc::TYPE_16UC1) {
264-
convert<uint16_t>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset,
267+
convert<uint16_t>(
268+
depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset,
265269
color_step);
266270
} else if (depth_msg->encoding == enc::TYPE_32FC1) {
267-
convert<float>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset,
271+
convert<float>(
272+
depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset,
268273
color_step);
269274
} else {
270275
RCLCPP_ERROR(logger_, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());

depth_image_proc/src/register.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -157,8 +157,9 @@ void RegisterNode::imageCb(
157157
Eigen::Affine3d depth_to_rgb;
158158
try {
159159
tf2::TimePoint tf2_time(std::chrono::nanoseconds(depth_info_msg->header.stamp.nanosec) +
160-
std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::seconds(
161-
depth_info_msg->header.stamp.sec)));
160+
std::chrono::duration_cast<std::chrono::nanoseconds>(
161+
std::chrono::seconds(
162+
depth_info_msg->header.stamp.sec)));
162163
geometry_msgs::msg::TransformStamped transform = tf_buffer_->lookupTransform(
163164
rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
164165
tf2_time);
@@ -186,7 +187,8 @@ void RegisterNode::imageCb(
186187
} else if (depth_image_msg->encoding == enc::TYPE_32FC1) {
187188
convert<float>(depth_image_msg, registered_msg, depth_to_rgb);
188189
} else {
189-
RCLCPP_ERROR(logger_, "Depth image has unsupported encoding [%s]",
190+
RCLCPP_ERROR(
191+
logger_, "Depth image has unsupported encoding [%s]",
190192
depth_image_msg->encoding.c_str());
191193
return;
192194
}

image_proc/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ find_package(rcutils REQUIRED)
1818
find_package(cv_bridge REQUIRED)
1919
find_package(image_transport REQUIRED)
2020
find_package(sensor_msgs REQUIRED)
21-
find_package(OpenCV 3 REQUIRED)
21+
find_package(OpenCV 4 REQUIRED)
2222
find_package(image_geometry REQUIRED)
2323

2424
include_directories(

image_proc/src/crop_decimate.cpp

Lines changed: 13 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -46,11 +46,7 @@ void debayer2x2toBGR(
4646
int R, int G1, int G2, int B)
4747
{
4848
typedef cv::Vec<T, 3> DstPixel; // 8- or 16-bit BGR
49-
#if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION > 2
5049
dst.create(src.rows / 2, src.cols / 2, cv::traits::Type<DstPixel>::value);
51-
#else
52-
dst.create(src.rows / 2, src.cols / 2, cv::DataType<DstPixel>::type);
53-
#endif
5450

5551
int src_row_step = src.step1();
5652
int dst_row_step = dst.step1();
@@ -120,8 +116,9 @@ CropDecimateNode::CropDecimateNode(const rclcpp::NodeOptions & options)
120116

121117
pub_ = image_transport::create_camera_publisher(this, "image_raw");
122118
sub_ = image_transport::create_camera_subscription(
123-
this, "image_raw", std::bind(&CropDecimateNode::imageCb, this,
124-
std::placeholders::_1, std::placeholders::_2), "raw");
119+
this, "image_raw", std::bind(
120+
&CropDecimateNode::imageCb, this,
121+
std::placeholders::_1, std::placeholders::_2), "raw");
125122
}
126123

127124
void CropDecimateNode::imageCb(
@@ -152,7 +149,8 @@ void CropDecimateNode::imageCb(
152149
int max_width = image_msg->width - offset_x_;
153150

154151
if (max_width <= 0) {
155-
RCLCPP_WARN(get_logger(),
152+
RCLCPP_WARN(
153+
get_logger(),
156154
"x offset is outside the input image width: "
157155
"%i, x offset: %i.", image_msg->width, offset_x_);
158156
return;
@@ -161,7 +159,8 @@ void CropDecimateNode::imageCb(
161159
int max_height = image_msg->height - offset_y_;
162160

163161
if (max_height <= 0) {
164-
RCLCPP_WARN(get_logger(),
162+
RCLCPP_WARN(
163+
get_logger(),
165164
"y offset is outside the input image height: "
166165
"%i, y offset: %i", image_msg->height, offset_y_);
167166
return;
@@ -200,7 +199,8 @@ void CropDecimateNode::imageCb(
200199
// Special case: when decimating Bayer images, we first do a 2x2 decimation to BGR
201200
if (is_bayer && (decimation_x > 1 || decimation_y > 1)) {
202201
if (decimation_x % 2 != 0 || decimation_y % 2 != 0) {
203-
RCLCPP_ERROR(get_logger(),
202+
RCLCPP_ERROR(
203+
get_logger(),
204204
"Odd decimation not supported for Bayer images");
205205
return;
206206
}
@@ -224,7 +224,8 @@ void CropDecimateNode::imageCb(
224224
} else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG16) {
225225
debayer2x2toBGR<uint16_t>(output.image, bgr, 1, 0, step + 1, step);
226226
} else {
227-
RCLCPP_ERROR(get_logger(), "Unrecognized Bayer encoding '%s'",
227+
RCLCPP_ERROR(
228+
get_logger(), "Unrecognized Bayer encoding '%s'",
228229
image_msg->encoding.c_str());
229230
return;
230231
}
@@ -271,7 +272,8 @@ void CropDecimateNode::imageCb(
271272
decimate<16>(output.image, decimated, decimation_x, decimation_y);
272273
break;
273274
default:
274-
RCLCPP_ERROR(get_logger(),
275+
RCLCPP_ERROR(
276+
get_logger(),
275277
"Unsupported pixel size, %d bytes", pixel_size);
276278
return;
277279
}

0 commit comments

Comments
 (0)