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

add image_flip node (backport #942) #1059

Merged
merged 1 commit into from
Dec 11, 2024
Merged
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
7 changes: 7 additions & 0 deletions image_rotate/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,13 @@ ament_auto_add_executable(image_rotate_bin src/image_rotate.cpp)
set_target_properties(image_rotate_bin PROPERTIES OUTPUT_NAME ${PROJECT_NAME})
target_link_libraries(image_rotate_bin ${OpenCV_LIBRARIES} ${PROJECT_NAME})

ament_auto_add_library(image_flip SHARED src/image_flip.cpp)
target_link_libraries(image_flip ${OpenCV_LIBRARIES})
rclcpp_components_register_node(image_flip
PLUGIN "${PROJECT_NAME}::ImageFlipNode"
EXECUTABLE image_flip_node
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
30 changes: 30 additions & 0 deletions image_rotate/doc/components.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,36 @@
Nodes and Components
====================

image_rotate::ImageFlipNode
-----------------------------
This is a simplified version image rotate which merely rotates/flips
the images.

Subscribed Topics
^^^^^^^^^^^^^^^^^
* **image** (sensor_msgs/Image): Image to be rotated.
* **camera_info** (sensor_msgs/CameraInfo): Camera metadata, only
used if ``use_camera_info`` is set to true.

Published Topics
^^^^^^^^^^^^^^^^
* **rotated/image** (sensor_msgs/Image): Rotated image.
* **out/camera_info** (sensor_msgs/CameraInfo): Camera metadata, with binning and
ROI fields adjusted to match output raw image.

Parameters
^^^^^^^^^^
* **output_frame_id** (str, default: ""): Frame to publish for the image's
new orientation. Empty means add '_rotated' suffix to the image frame.
* **use_camera_info** (bool, default: True): Indicates that the camera_info
topic should be subscribed to to get the default input_frame_id.
Otherwise the frame from the image message will be used.
* **rotation_steps** (int, default: 2): Number of times to rotate the image:

* 1 is transpose and flip in CCW
* 2 is flip (180 mirroring)
* 3 is transpose and flip in CW

image_rotate::ImageRotateNode
-----------------------------
Node to rotate an image for visualization. The node takes a source
Expand Down
103 changes: 103 additions & 0 deletions image_rotate/include/image_rotate/image_flip.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
// Copyright (c) 2022, CHRISLab, Christopher Newport University
// Copyright (c) 2008, Willow Garage, Inc.
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef IMAGE_ROTATE__IMAGE_FLIP_HPP_
#define IMAGE_ROTATE__IMAGE_FLIP_HPP_

#include <math.h>

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/static_transform_broadcaster.h>

#include <memory>
#include <string>

#include <cv_bridge/cv_bridge.hpp>
#include <image_transport/image_transport.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include "image_rotate/visibility.h"

namespace image_rotate
{

struct ImageFlipConfig
{
std::string output_frame_id;
int rotation_steps;
bool use_camera_info;
};

class ImageFlipNode : public rclcpp::Node
{
public:
IMAGE_ROTATE_PUBLIC ImageFlipNode(rclcpp::NodeOptions options);

private:
const std::string frameWithDefault(const std::string & frame, const std::string & image_frame);
void imageCallbackWithInfo(
const sensor_msgs::msg::Image::ConstSharedPtr & msg,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & cam_info);
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg);
void do_work(
const sensor_msgs::msg::Image::ConstSharedPtr & msg,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & cam_info,
const std::string input_frame_from_msg);
void onInit();

rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handle_;

std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_sub_;
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> tf_pub_;
bool tf_unpublished_;

ImageFlipConfig config_;

// Subscriber - only one is used at a time - depends on use_camera_info
image_transport::Subscriber img_sub_;
image_transport::CameraSubscriber cam_sub_;

// Publisher - only one is used at a time - depends on use_camera_info
image_transport::Publisher img_pub_;
image_transport::CameraPublisher cam_pub_;

double angle_;
tf2::TimePoint prev_stamp_;
geometry_msgs::msg::TransformStamped transform_;
};
} // namespace image_rotate

#endif // IMAGE_ROTATE__IMAGE_FLIP_HPP_
3 changes: 2 additions & 1 deletion image_rotate/include/image_rotate/image_rotate_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,13 +93,14 @@ class ImageRotateNode : public rclcpp::Node
image_rotate::ImageRotateConfig config_;

image_transport::Publisher img_pub_;

// Subscriber - only one is used at a time - depends on use_camera_info
image_transport::Subscriber img_sub_;
image_transport::CameraSubscriber cam_sub_;

geometry_msgs::msg::Vector3Stamped target_vector_;
geometry_msgs::msg::Vector3Stamped source_vector_;

int subscriber_count_;
double angle_;
tf2::TimePoint prev_stamp_;
};
Expand Down
49 changes: 49 additions & 0 deletions image_rotate/launch/image_flip.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
# Copyright (c) 2022, CHRISLab, Christopher Newport University
# All rights reserved.
#
# Software License Agreement (BSD License 2.0)
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of the Willow Garage nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

"""Demonstration of basic launch of the image_flip_node with remappings."""

from launch import LaunchDescription
import launch_ros.actions


def generate_launch_description():
"""Launch description for basic launch of the image_flip."""
return LaunchDescription([
launch_ros.actions.Node(
package='image_rotate', executable='image_flip',
output='screen', name='camera_flip',
remappings=[('image', 'camera/rgb/image_raw'),
('rotated/image', 'camera_rotated/image_rotated')],
parameters=[{'output_frame_id': 'camera_rotated',
'rotation_steps': 2,
'use_camera_info': True}])])
1 change: 1 addition & 0 deletions image_rotate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
<url type="bugtracker">https://github.com/ros-perception/image_pipeline/issues</url>
<url type="repository">https://github.com/ros-perception/image_pipeline</url>
<author>Blaise Gassend</author>
<author email="[email protected]">David Conner</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

Expand Down
Loading
Loading