1313#include < memory>
1414#include < string>
1515#include < unordered_map>
16+ #include < vector>
1617
1718#include " cv_bridge/cv_bridge.h"
1819#include " opencv2/dnn.hpp"
@@ -24,13 +25,16 @@ enum NormalizationTypes
2425{
2526 kNone ,
2627 kUnitScaling ,
27- kPositiveNegative
28+ kPositiveNegative ,
29+ kImageNormalization
2830};
2931
3032const std::unordered_map<std::string, int32_t > g_str_to_normalization_type ({
3133 {" none" , NormalizationTypes::kNone },
3234 {" unit_scaling" , NormalizationTypes::kUnitScaling },
33- {" positive_negative" , NormalizationTypes::kPositiveNegative }});
35+ {" positive_negative" , NormalizationTypes::kPositiveNegative },
36+ {" image_normalization" , NormalizationTypes::kImageNormalization }}
37+ );
3438
3539const std::unordered_map<std::string, std::string> g_str_to_image_encoding ({
3640 {" rgb8" , sensor_msgs::image_encodings::RGB8},
@@ -53,6 +57,10 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
5357 std::string image_encoding_;
5458 std::string normalization_type_;
5559 std::string tensor_name_;
60+ bool maintain_aspect_ratio_;
61+ bool center_crop_;
62+ std::vector<double > image_mean_;
63+ std::vector<double > image_stddev_;
5664
5765 void Initialize (DnnImageEncoderNode * encoder_node)
5866 {
@@ -62,6 +70,10 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
6270 image_encoding_ = node->network_image_encoding_ ;
6371 normalization_type_ = node->network_normalization_type_ ;
6472 tensor_name_ = node->tensor_name_ ;
73+ maintain_aspect_ratio_ = node->maintain_aspect_ratio_ ;
74+ center_crop_ = node->center_crop_ ;
75+ image_mean_ = node->image_mean_ ;
76+ image_stddev_ = node->image_stddev_ ;
6577 }
6678
6779 isaac_ros_nvengine_interfaces::msg::TensorList OnCallback (
@@ -73,6 +85,39 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
7385
7486 // Resize the image to the user specified dimensions
7587 cv::Mat image_resized;
88+
89+ if (maintain_aspect_ratio_) {
90+ const double width_ratio = static_cast <double >(image_msg->width ) /
91+ static_cast <double >(image_width_);
92+ const double height_ratio = static_cast <double >(image_msg->height ) /
93+ static_cast <double >(image_height_);
94+ cv::Size size;
95+ if (height_ratio < width_ratio) { // Cropping width
96+ const double target_ratio = static_cast <double >(image_width_) /
97+ static_cast <double >(image_height_);
98+ const double crop_height = image_msg->height ;
99+ // Make sure the amount cropped is less than or equal to the current width of image
100+ const bool cropped_less = target_ratio * image_msg->height < image_msg->width ;
101+ const double crop_width =
102+ (cropped_less) ? target_ratio * image_msg->height : image_msg->width ;
103+ cv::Rect cropped_area (
104+ (center_crop_) ? (static_cast <double >(image_msg->width ) - crop_width) / 2.0 : 0 ,
105+ 0 , crop_width, crop_height);
106+ image_ptr->image = image_ptr->image (cropped_area);
107+ } else { // Cropping height
108+ const double target_ratio = static_cast <double >(image_height_) /
109+ static_cast <double >(image_width_);
110+ const double crop_width = image_msg->width ;
111+ // Make sure the amount cropped is less than or equal to the current height of image
112+ const bool cropped_less = target_ratio * image_msg->width < image_msg->height ;
113+ const double crop_height =
114+ (cropped_less) ? target_ratio * image_msg->width : image_msg->height ;
115+ cv::Rect cropped_area (0 ,
116+ (center_crop_) ? (static_cast <double >(image_msg->height ) - crop_height) / 2.0 : 0 ,
117+ crop_width, crop_height);
118+ image_ptr->image = image_ptr->image (cropped_area);
119+ }
120+ }
76121 cv::resize (image_ptr->image , image_resized, cv::Size (image_width_, image_height_));
77122
78123 // Normalize tensor depending on normalization type required
@@ -83,6 +128,16 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
83128 case NormalizationTypes::kPositiveNegative :
84129 image_resized.convertTo (image_resized, CV_32F, 2 .0f / 255 .0f , -1 .0f );
85130 break ;
131+ case NormalizationTypes::kImageNormalization :
132+ image_resized.convertTo (image_resized, CV_32F);
133+ image_resized.forEach <cv::Vec3f>(
134+ [this ](cv::Vec3f & pixel, const int *) -> void
135+ {
136+ pixel[0 ] = (pixel[0 ] / 255 .0f - image_mean_[0 ]) / image_stddev_[0 ];
137+ pixel[1 ] = (pixel[1 ] / 255 .0f - image_mean_[1 ]) / image_stddev_[1 ];
138+ pixel[2 ] = (pixel[2 ] / 255 .0f - image_mean_[2 ]) / image_stddev_[2 ];
139+ });
140+ break ;
86141 default :
87142 image_resized.convertTo (image_resized, CV_32F);
88143 }
@@ -126,6 +181,10 @@ DnnImageEncoderNode::DnnImageEncoderNode(const rclcpp::NodeOptions options)
126181 network_image_width_ (declare_parameter<int >(" network_image_width" , 224 )),
127182 network_image_height_(declare_parameter<int >(" network_image_height" , 224 )),
128183 network_image_encoding_(declare_parameter<std::string>(" network_image_encoding" , " rgb8" )),
184+ maintain_aspect_ratio_(declare_parameter<bool >(" maintain_aspect_ratio" , false )),
185+ center_crop_(declare_parameter<bool >(" center_crop" , false )),
186+ image_mean_(declare_parameter<std::vector<double >>(" image_mean" , {0.5 , 0.5 , 0.5 })),
187+ image_stddev_(declare_parameter<std::vector<double >>(" image_stddev" , {0.5 , 0.5 , 0.5 })),
129188 tensor_name_(declare_parameter<std::string>(" tensor_name" , " input" )),
130189 network_normalization_type_(declare_parameter<std::string>(
131190 " network_normalization_type" , " unit_scaling" )),
@@ -155,6 +214,13 @@ DnnImageEncoderNode::DnnImageEncoderNode(const rclcpp::NodeOptions options)
155214 network_normalization_type_);
156215 }
157216
217+ if (network_normalization_type_ == " image_normalization" &&
218+ (image_mean_.size () != 3 || image_stddev_.size () != 3 ))
219+ {
220+ throw std::runtime_error (
221+ " Error: if normalization type is set to Image Normalization, vectors image_mean "
222+ " and image_stddev must have exactly 3 elements" );
223+ }
158224 impl_->Initialize (this );
159225}
160226
0 commit comments