Skip to content

Commit

Permalink
Add flip functionality
Browse files Browse the repository at this point in the history
Implemented with reference to
ERAU-Projects/usb_cam@89dd4ca
Changes:
1. Uses latest version of usb_cam
2. Uses OpenCV cv2
3. Cleaner flip implementation
Please pass parameters in from launch file
  • Loading branch information
kaikwan committed Aug 2, 2024
1 parent 15dd884 commit 2aab285
Show file tree
Hide file tree
Showing 3 changed files with 40 additions and 0 deletions.
2 changes: 2 additions & 0 deletions include/usb_cam/usb_cam.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,8 @@ class UsbCam: public AbstractV4LUSBCam
std_srvs::Trigger::Response& response);

/* Node parameters */
static bool img_flip_;
static int img_flip_code_;
static std::string camera_name;
static std::string camera_frame_id;
static std::string camera_transport_suffix;
Expand Down
16 changes: 16 additions & 0 deletions launch/usb_cam-test_flip.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video1" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="image_flip" value="true"/>
<param name="image_flip_code" value="0"/>
</node>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_raw"/>
<param name="autosize" value="true" />
</node>
</launch>
22 changes: 22 additions & 0 deletions src/usb_cam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
#include <vector>
#include "ros/service_server.h"
#include "usb_cam/usb_cam.h"
#include <opencv2/core.hpp>

using namespace usb_cam;

Expand All @@ -59,6 +60,8 @@ ros::ServiceServer* UsbCam::service_supported_controls = nullptr;
image_transport::ImageTransport* UsbCam::image_transport = nullptr;

/* Node parameters */
bool UsbCam::img_flip_ = 0;
int UsbCam::img_flip_code_ = 0;
std::string UsbCam::camera_name = "head_camera";
std::string UsbCam::camera_frame_id = "head_camera";
std::string UsbCam::camera_transport_suffix = "image_raw";
Expand Down Expand Up @@ -138,6 +141,16 @@ UsbCam::UsbCam():
node.getParam("framerate", framerate);
node.param<std::string>("start_service_name", _service_start_name, "start_capture");
node.param<std::string>("stop_service_name", _service_stop_name, "stop_capture");
node.getParam("image_flip", img_flip_);
node.getParam("image_flip_code", img_flip_code_);

// Protect user from themselves. Warns if you forgot one of the two tags.
if (node.hasParam("image_flip") != node.hasParam("image_flip_code"))
{
img_flip_ = false;
img_flip_code_ = 0;
ROS_ERROR("Both the \"image_flip\" and the \"image_flip_code\" parameters must be set to flip an image.");
}

// Advertising camera
ROS_INFO("Initializing ROS V4L USB camera '%s' (%s) at %dx%d via %s (%s) at %i FPS",
Expand Down Expand Up @@ -298,6 +311,15 @@ int UsbCam::frame_timer_callback(const ros::TimerEvent& event)
ros::shutdown();
return -1; // Return an error code
}
if(img_flip_)
{
cv::Mat original_mat(new_image->height, new_image->width, CV_8UC3, &new_image->image[0]);
cv::Mat flipped_mat;
cv::flip(original_mat, flipped_mat, img_flip_code_);
// Copy the flipped image back to new_image
memcpy(new_image->image, flipped_mat.data, new_image->step * new_image->height);
}

img_msg->header.stamp.sec = new_image->stamp.tv_sec;
img_msg->header.stamp.nsec = new_image->stamp.tv_nsec;
if (img_msg->data.size() != static_cast<size_t>(new_image->step * new_image->height))
Expand Down

0 comments on commit 2aab285

Please sign in to comment.