Skip to content

Commit

Permalink
Merge branch 'develop' into feature/avoid-image-copy
Browse files Browse the repository at this point in the history
# Conflicts:
#	src/proc_image_processing/cpu/filters/low_pass/contrast_and_brightness_filter.h
#	src/proc_image_processing/cpu/filters/low_pass/equalize_filter.h
#	src/proc_image_processing/cpu/filters/low_pass/subtract_all_planes_filter.h
#	src/proc_image_processing/cpu/filters/low_pass/subtract_plane_adder_filter.h
#	src/proc_image_processing/cpu/filters/low_pass/thresholds/hsv_threshold_filter.h
#	src/proc_image_processing/cpu/filters/transformations/rotate_filter.h
  • Loading branch information
ProgHunter committed Aug 8, 2021
2 parents 59e44d2 + 1931adb commit 5172484
Show file tree
Hide file tree
Showing 45 changed files with 1,344 additions and 1,493 deletions.
66 changes: 31 additions & 35 deletions src/proc_image_processing/cpu/filters/custom/accumulator_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ namespace proc_image_processing {
explicit AccumulatorFilter(const GlobalParamHandler &globalParams)
: Filter(globalParams),
accumulator_(3, cv::Size(0, 0), CV_8UC1),
enable_("Enable", false, &parameters_),
nb_image_("NB_of_images", 3, 1, 20, &parameters_),
method_("Method_to_use", 1, 0, 2, &parameters_,
"Method: 1=SameWeight, 2=Adding50Percent, 3=Adjusted"),
Expand All @@ -31,48 +30,45 @@ namespace proc_image_processing {
~AccumulatorFilter() override = default;

void apply(cv::Mat &image) override {
if (enable_()) {
// Is there any change in the type of images
// we input to the accumulator?
// If yes, reset it.
if (last_type_ != image.type() || last_method_ != method_() ||
last_nb_image_ != nb_image_() || last_size_ != image.size()) {
accumulator_.resetBuffer(nb_image_(), image.size(), image.type());
// Is there any change in the type of images
// we input to the accumulator?
// If yes, reset it.
if (last_type_ != image.type() || last_method_ != method_() ||
last_nb_image_ != nb_image_() || last_size_ != image.size()) {
accumulator_.resetBuffer(nb_image_(), image.size(), image.type());

last_nb_image_ = nb_image_();
last_size_ = image.size();
last_nb_image_ = nb_image_();
last_size_ = image.size();

switch (method_()) {
case 0:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_ALL_SAME_WEIGHT);
break;
case 1:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_50_PERCENT);
break;
case 2:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_ADJUST_WEIGHT);
break;
default:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_ALL_SAME_WEIGHT);
break;
}
last_method_ = method_();
last_type_ = image.type();
switch (method_()) {
case 0:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_ALL_SAME_WEIGHT);
break;
case 1:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_50_PERCENT);
break;
case 2:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_ADJUST_WEIGHT);
break;
default:
accumulator_.setAverageMethod(
ImageAccumulatorBuffer::ACC_ALL_SAME_WEIGHT);
break;
}
// Add the newest frame
accumulator_.addImage(image);
// Change the input for the newest averaging.
accumulator_.convertImage(image);
last_method_ = method_();
last_type_ = image.type();
}
// Add the newest frame
accumulator_.addImage(image);
// Change the input for the newest averaging.
accumulator_.convertImage(image);
}

private:
ImageAccumulatorBuffer accumulator_;
Parameter<bool> enable_;
RangedParameter<int> nb_image_, method_;
// Here we need some sorte of remembering
// so we can reset the accumulator on
Expand Down
77 changes: 37 additions & 40 deletions src/proc_image_processing/cpu/filters/custom/deep_2019_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ namespace proc_image_processing {
explicit Deep2019Filter(const GlobalParamHandler &globalParams) :
Filter(globalParams),
nh_(ros::NodeHandle("proc_image_processing")),
enable_("Enable", false, &parameters_),
debug_contour_("Debug contour", false, &parameters_),
vetalas_("Vetalas", true, &parameters_),
draugr_("Draugr", true, &parameters_),
Expand All @@ -37,46 +36,44 @@ namespace proc_image_processing {
~Deep2019Filter() override { image_subscriber_.shutdown(); }

void apply(cv::Mat &image) override {
if (enable_()) {
Target target;
image_width_ = image.size().width;
image_height_ = image.size().height;

for (auto &object : bounding_box_) {
if (vetalas_.getValue() && object.class_name.data == vetalas_.getName()) {
color_ = cv::Scalar(0, 0, 255);
handleObject(target, object, image, color_);
}
if (draugr_.getValue() && object.class_name.data == draugr_.getName()) {
color_ = cv::Scalar(0, 255, 0);
handleObject(target, object, image, color_);
}
if (jiangshi_.getValue() && object.class_name.data == jiangshi_.getName()) {
color_ = cv::Scalar(255, 0, 0);
handleObject(target, object, image, color_);
}
if (answag_.getValue() && object.class_name.data == answag_.getName()) {
color_ = cv::Scalar(244, 185, 66);
handleObject(target, object, image, color_);
}
if (vampire_.getValue() && object.class_name.data == vampire_.getName()) {
color_ = cv::Scalar(200, 185, 66);
handleObject(target, object, image, color_);
}
if (bat_.getValue() && object.class_name.data == bat_.getName()) {
color_ = cv::Scalar(217, 244, 66);
handleObject(target, object, image, color_);
}
if (wolf_.getValue() && object.class_name.data == wolf_.getName()) {
color_ = cv::Scalar(66, 244, 223);
handleObject(target, object, image, color_);
}
Target target;
image_width_ = image.size().width;
image_height_ = image.size().height;

for (auto &object : bounding_box_) {
if (vetalas_.getValue() && object.class_name.data == vetalas_.getName()) {
color_ = cv::Scalar(0, 0, 255);
handleObject(target, object, image, color_);
}

for (int i = 0; i < (int) objects_.size(); ++i) {
notify(objects_.back());
objects_.pop_back();
if (draugr_.getValue() && object.class_name.data == draugr_.getName()) {
color_ = cv::Scalar(0, 255, 0);
handleObject(target, object, image, color_);
}
if (jiangshi_.getValue() && object.class_name.data == jiangshi_.getName()) {
color_ = cv::Scalar(255, 0, 0);
handleObject(target, object, image, color_);
}
if (answag_.getValue() && object.class_name.data == answag_.getName()) {
color_ = cv::Scalar(244, 185, 66);
handleObject(target, object, image, color_);
}
if (vampire_.getValue() && object.class_name.data == vampire_.getName()) {
color_ = cv::Scalar(200, 185, 66);
handleObject(target, object, image, color_);
}
if (bat_.getValue() && object.class_name.data == bat_.getName()) {
color_ = cv::Scalar(217, 244, 66);
handleObject(target, object, image, color_);
}
if (wolf_.getValue() && object.class_name.data == wolf_.getName()) {
color_ = cv::Scalar(66, 244, 223);
handleObject(target, object, image, color_);
}
}

for (int i = 0; i < (int) objects_.size(); ++i) {
notify(objects_.back());
objects_.pop_back();
}
};

Expand All @@ -91,7 +88,7 @@ namespace proc_image_processing {
ros::NodeHandle nh_;
std::vector<sonia_common::Detection> bounding_box_;
std::vector<Target> objects_;
Parameter<bool> enable_, debug_contour_, vetalas_, draugr_, jiangshi_, answag_, vampire_, bat_, wolf_;
Parameter<bool> debug_contour_, vetalas_, draugr_, jiangshi_, answag_, vampire_, bat_, wolf_;
int image_width_{};
int image_height_{};
cv::Scalar color_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ namespace proc_image_processing {

explicit HideSubmarineFrameFilter(const GlobalParamHandler &globalParams)
: Filter(globalParams),
enable_("Enable", false, &parameters_),
rotate_type_("Rotation_type", 0, 0, 3, &parameters_,
"RotateFilter type: 0=NONE, 1=x axis, 2=y axis, 3=all axis"),
prev_rot_value_(0) {
Expand All @@ -28,30 +27,27 @@ namespace proc_image_processing {
~HideSubmarineFrameFilter() override = default;

void apply(cv::Mat &image) override {
if (enable_()) {
if (prev_rot_value_ != rotate_type_()) {
prev_rot_value_ = rotate_type_();
switch (rotate_type_()) {
case 1:
cv::flip(bottom_mask_, bottom_mask_, 0);
break;
case 2:
cv::flip(bottom_mask_, bottom_mask_, 1);
break;
case 3:
cv::flip(bottom_mask_, bottom_mask_, -1);
break;
default:
break;
}
if (prev_rot_value_ != rotate_type_()) {
prev_rot_value_ = rotate_type_();
switch (rotate_type_()) {
case 1:
cv::flip(bottom_mask_, bottom_mask_, 0);
break;
case 2:
cv::flip(bottom_mask_, bottom_mask_, 1);
break;
case 3:
cv::flip(bottom_mask_, bottom_mask_, -1);
break;
default:
break;
}
if (image.size() == bottom_mask_.size())
cv::bitwise_and(image, bottom_mask_, image);
}
if (image.size() == bottom_mask_.size())
cv::bitwise_and(image, bottom_mask_, image);
}

private:
Parameter<bool> enable_;
RangedParameter<int> rotate_type_;
cv::Mat bottom_mask_;
int prev_rot_value_;
Expand Down
46 changes: 18 additions & 28 deletions src/proc_image_processing/cpu/filters/custom/in_range_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ namespace proc_image_processing {

explicit InRangeFilter(const GlobalParamHandler &globalParams)
: Filter(globalParams),
enable_("Enable", false, &parameters_),
lower_hue_("HSVLowH", 0, 0, 255, &parameters_),
upper_hue_("HSVHighH", 255, 0, 255, &parameters_),
lower_saturation_("HSVLowS", 0, 0, 255, &parameters_),
Expand All @@ -47,36 +46,27 @@ namespace proc_image_processing {
* \param image The image to process.
*/
void apply(cv::Mat &image) override {
if (enable_.getValue()) {
cv::Mat hsv;
cv::Mat luv;

cv::cvtColor(image, hsv, cv::COLOR_RGB2HSV_FULL);
cv::inRange(
hsv, cv::Scalar(lower_hue_.getValue(), lower_saturation_.getValue(),
lower_value_.getValue()),
cv::Scalar(upper_hue_.getValue(), upper_saturation_.getValue(),
upper_value_.getValue()),
hsv);

cv::cvtColor(image, luv, cv::COLOR_RGB2Luv);
cv::inRange(luv, cv::Scalar(lower_lightness_.getValue(),
lower_u_.getValue(), lower_v_.getValue()),
cv::Scalar(upper_lightness_.getValue(), upper_u_.getValue(),
upper_v_.getValue()),
luv);
cv::bitwise_and(hsv, luv, image);
}
cv::Mat hsv;
cv::Mat luv;

cv::cvtColor(image, hsv, cv::COLOR_RGB2HSV_FULL);
cv::inRange(
hsv, cv::Scalar(lower_hue_.getValue(), lower_saturation_.getValue(),
lower_value_.getValue()),
cv::Scalar(upper_hue_.getValue(), upper_saturation_.getValue(),
upper_value_.getValue()),
hsv);

cv::cvtColor(image, luv, cv::COLOR_RGB2Luv);
cv::inRange(luv, cv::Scalar(lower_lightness_.getValue(),
lower_u_.getValue(), lower_v_.getValue()),
cv::Scalar(upper_lightness_.getValue(), upper_u_.getValue(),
upper_v_.getValue()),
luv);
cv::bitwise_and(hsv, luv, image);
}

private:
/**
* State if the filter is enabled or not.
* This is being used by the vision server for calling the filter in the
* filterchain.
*/
Parameter<bool> enable_;

/** Inclusive Hue lower boundary. */
RangedParameter<int> lower_hue_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,17 @@ namespace proc_image_processing {

explicit MissionTestFakeStringFilter(const GlobalParamHandler &globalParams)
: Filter(globalParams),
enable_("Enable", false, &parameters_),
_string("String_to_return", "test", &parameters_) {
setName("MissionTestFakeStringFilter");
}

~MissionTestFakeStringFilter() override = default;

void apply(cv::Mat &image) override {
if (enable_()) {
notify(Target());
}
notify(Target());
}

private:
Parameter<bool> enable_;
Parameter <std::string> _string;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,20 +13,15 @@ namespace proc_image_processing {
using Ptr = std::shared_ptr<OriginalImageFilter>;

explicit OriginalImageFilter(const GlobalParamHandler &globalParams)
: Filter(globalParams), enable_("Enable", false, &parameters_) {
: Filter(globalParams) {
setName("OriginalImageFilter");
}

~OriginalImageFilter() override = default;

void apply(cv::Mat &image) override {
if (enable_()) {
image = global_params_.getOriginalImage();
}
image = global_params_.getOriginalImage();
}

private:
Parameter<bool> enable_;
};

} // namespace proc_image_processing
Expand Down
16 changes: 6 additions & 10 deletions src/proc_image_processing/cpu/filters/custom/test_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ namespace proc_image_processing {

explicit TestFilter(const GlobalParamHandler &globalParams)
: Filter(globalParams),
enable_("Enable", true, &parameters_),
x_("X", 0, -512, 512, &parameters_),
y_("Y", 0, -512, 512, &parameters_),
w_("Width", 200, 0, 1024, &parameters_),
Expand All @@ -32,18 +31,15 @@ namespace proc_image_processing {
virtual void init() {}

void apply(cv::Mat &image) override {
if (enable_()) {
target_.setTarget("test_filter", x_.getValue() - 1000 / 2, y_.getValue(),
w_.getValue(), h_.getValue(), angle_.getValue(), 1000,
-1000 - (1000 / 2), specField1_.getValue(),
specField2_.getValue());

notify(target_);
}
target_.setTarget("test_filter", x_.getValue() - 1000 / 2, y_.getValue(),
w_.getValue(), h_.getValue(), angle_.getValue(), 1000,
-1000 - (1000 / 2), specField1_.getValue(),
specField2_.getValue());

notify(target_);
}

private:
Parameter<bool> enable_;
RangedParameter<int> x_, y_, w_, h_, angle_;
Parameter <std::string> header_, specField1_, specField2_;

Expand Down
Loading

0 comments on commit 5172484

Please sign in to comment.