Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added flip option in camera.cpp #36

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,4 @@
*.a

*~
.DS_Store
6 changes: 6 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.

Expand Down
10 changes: 10 additions & 0 deletions include/cv_camera/capture.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
16 changes: 16 additions & 0 deletions launch/arducam_camera_publish.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<!-- adapted for use with ArduCam -->
<launch>
<node pkg="cv_camera" type="cv_camera_node" name="cv_camera" output="screen">
<!-- minimum size for ardu cam is 640 x 480 -->
<param name="image_width" value="640"/>
<param name="image_height" value="480"/>
<param name="rate" value="30"/>
<param name="frame_id" value="camera"/>
<!-- Need to be able to change the device ID default is 0 , wich is the deskcam in a laptop -->
<param name="device_id" value="2"/>
<!-- ArduCam is mounted upside down on turtlebot3, needs flipping, available in adpated cv_camera-->
<param name="flip_image" value="true"/>
<param name="image_flip_code" value="-1"/>

</node>
</launch>
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>cv_camera</name>
<version>0.6.0</version>
<version>0.6.1</version>
<description>cv_camera uses OpenCV capture object to capture camera image.
This supports camera_image and nodelet.
</description>
Expand Down
10 changes: 10 additions & 0 deletions src/capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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)
{
Expand Down