diff --git a/.gitignore b/.gitignore
index 23a6326..6de276b 100644
--- a/.gitignore
+++ b/.gitignore
@@ -13,3 +13,4 @@
*.a
*~
+.DS_Store
diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index aec5351..2f081b9 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -2,6 +2,12 @@
Changelog for package cv_camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+0.6.1 (2022_02-24)
+* Adding option to flip image at source using cv::flip function.
+ Useful for cameras mounted upside down, without the option to
+ flip the image in the camera, i.e. ArduCam
+* Contributors: Skammi
+
0.6.0 (2021-07-06)
------------------
* Adding MONO8 format if number of channels is 1
diff --git a/README.md b/README.md
index a4ddd19..1b86e05 100644
--- a/README.md
+++ b/README.md
@@ -33,6 +33,8 @@ If no calibration data is set, it has dummy values except for width and height.
* `~capture_delay` (*double*, default: 0) – estimated duration of capturing and receiving the image.
* `~rescale_camera_info` (*bool*, default: false) – rescale camera calibration info automatically.
* `~camera_name` (*bool*, default: same as `frame_id`) – camera name for `camera_info_manager`.
+* `~flip_image` (*bool*, default: false) – flip the image according to image_flip_code.
+* `~image_flip_code` (*int*, default: -1) – code to flip the image see cv::flip() for description.
Supports CV_CAP_PROP_*, by below params.
diff --git a/include/cv_camera/capture.h b/include/cv_camera/capture.h
index 942c60f..97d9641 100644
--- a/include/cv_camera/capture.h
+++ b/include/cv_camera/capture.h
@@ -220,6 +220,16 @@ class Capture
* @brief capture_delay param value
*/
ros::Duration capture_delay_;
+
+ // Skammi extension
+ /**
+ * @brief
+ * flip parameter value true or false
+ * image_flip_code parameter value see opencv flip
+ */
+ bool flip_image_ {false}; // Image to be flipped, default false
+ int image_flip_code_ {-1}; // Default horizontal and vertical
+
};
} // namespace cv_camera
diff --git a/launch/arducam_camera_publish.launch b/launch/arducam_camera_publish.launch
new file mode 100644
index 0000000..4e4d2ad
--- /dev/null
+++ b/launch/arducam_camera_publish.launch
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/package.xml b/package.xml
index 2908562..1270269 100644
--- a/package.xml
+++ b/package.xml
@@ -1,7 +1,7 @@
cv_camera
- 0.6.0
+ 0.6.1
cv_camera uses OpenCV capture object to capture camera image.
This supports camera_image and nodelet.
diff --git a/src/capture.cpp b/src/capture.cpp
index fbba0fb..f8579d5 100644
--- a/src/capture.cpp
+++ b/src/capture.cpp
@@ -20,6 +20,10 @@ Capture::Capture(ros::NodeHandle &node, const std::string &topic_name,
info_manager_(node_, camera_name),
capture_delay_(ros::Duration(node_.param("capture_delay", 0.0)))
{
+ // Skammi Extension
+ // Get the flip parameters
+ node_.param("flip_image", flip_image_, flip_image_);
+ node_.param("image_flip_code", image_flip_code_, image_flip_code_);
}
void Capture::loadCameraInfo()
@@ -137,6 +141,12 @@ bool Capture::capture()
bridge_.header.stamp = stamp;
bridge_.header.frame_id = frame_id_;
+ // Skammi extension
+ // Flip the image?
+ if (flip_image_) {
+ cv::flip(bridge_.image, bridge_.image, image_flip_code_);
+ }
+
info_ = info_manager_.getCameraInfo();
if (info_.height == 0 && info_.width == 0)
{