@@ -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
127124void 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