Skip to content

Commit

Permalink
clean up based on PR workflow
Browse files Browse the repository at this point in the history
  • Loading branch information
David Conner committed Dec 7, 2022
1 parent f168ae1 commit 135a1da
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 73 deletions.
7 changes: 0 additions & 7 deletions image_flip/CHANGELOG.rst

This file was deleted.

47 changes: 0 additions & 47 deletions image_flip/cfg/ImageFlip.cfg

This file was deleted.

14 changes: 6 additions & 8 deletions image_flip/include/image_flip/image_flip_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,18 +33,18 @@
#ifndef IMAGE_FLIP__IMAGE_FLIP_NODE_HPP_
#define IMAGE_FLIP__IMAGE_FLIP_NODE_HPP_

#include <rclcpp/rclcpp.hpp>
#include <math.h>
#include <memory>
#include <string>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/static_transform_broadcaster.h>
#include <image_transport/image_transport.hpp>
#include <cv_bridge/cv_bridge.h>
#include "image_flip/visibility.h"
#include <image_transport/image_transport.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <math.h>
#include <memory>
#include <string>

#include "image_flip/visibility.h"

namespace image_flip
{
Expand All @@ -56,7 +56,6 @@ struct ImageFlipConfig
bool use_camera_info;
std::string in_image_topic_name;
std::string out_image_topic_name;

};

class ImageFlipNode : public rclcpp::Node
Expand Down Expand Up @@ -98,7 +97,6 @@ class ImageFlipNode : public rclcpp::Node
double angle_;
tf2::TimePoint prev_stamp_;
geometry_msgs::msg::TransformStamped transform_;

};
} // namespace image_flip

Expand Down
4 changes: 2 additions & 2 deletions image_flip/launch/image_flip.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@
def generate_launch_description():
return LaunchDescription([
launch_ros.actions.Node(
package='image_rotate', node_executable='image_rotate', output='screen',
package='image_flip', node_executable='image_flip', output='screen',
remappings=[('image', '/camera/rgb/image_raw'),
('camera_info', '/camera/rgb/camera_info'),
('output_image', '/camera/rotated/image_raw'),
('output_camera_info', '/camera/rotated/camera_info']),
('output_camera_info', '/camera/rotated/camera_info')]),
])
16 changes: 7 additions & 9 deletions image_flip/src/image_flip_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,12 +138,12 @@ void ImageFlipNode::do_work(
// based on https://stackoverflow.com/questions/15043152/rotate-opencv-matrix-by-90-180-270-degrees
if (config_.rotation_steps == 1) {
transpose(in_image, out_image);
flip(out_image, out_image,0); //transpose+flip(0)=CCW
flip(out_image, out_image, 0); //transpose+flip(0)=CCW
} else if (config_.rotation_steps ==2){
flip(in_image, out_image,-1); //flip(-1)=180
flip(in_image, out_image, -1); //flip(-1)=180
} else if (config_.rotation_steps == 3){
transpose(in_image, out_image);
flip(out_image, out_image,1); //transpose+flip(1)=CW
flip(out_image, out_image, 1); //transpose+flip(1)=CW
} else if (config_.rotation_steps == 0) {
// Simple pass through
out_image = in_image;
Expand All @@ -164,8 +164,7 @@ void ImageFlipNode::do_work(
out_info->height = out_img->height;
out_info->width = out_img->width;
cam_pub_.publish(out_img, out_info);
}
else {
} else {
img_pub_.publish(out_img);
}

Expand Down Expand Up @@ -197,17 +196,17 @@ void ImageFlipNode::subscribe()
RCUTILS_LOG_INFO("Subscribing to image topic %s.", image_topic.c_str());

if (config_.use_camera_info) {
auto custom_qos = rmw_qos_profile_sensor_data; // To match Gazebo 11 pub
auto custom_qos = rmw_qos_profile_sensor_data; // To match Gazebo 11 pub
cam_sub_ = image_transport::create_camera_subscription(
this,
image_topic, //"image",
image_topic, //"image",
std::bind(
&ImageFlipNode::imageCallbackWithInfo, this,
std::placeholders::_1, std::placeholders::_2),
"raw",
custom_qos);
} else {
auto custom_qos = rmw_qos_profile_sensor_data; // To match Gazebo 11 pub
auto custom_qos = rmw_qos_profile_sensor_data; // To match Gazebo 11 pub
img_sub_ = image_transport::create_subscription(
this,
image_topic, //"image",
Expand Down Expand Up @@ -274,7 +273,6 @@ void ImageFlipNode::onInit()

tf_pub_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(*this);
tf_unpublished_ = true;

}
} // namespace image_flip

Expand Down

0 comments on commit 135a1da

Please sign in to comment.