Skip to content

Commit

Permalink
Merge pull request #14 from rogy-AquaLab/imshow
Browse files Browse the repository at this point in the history
imshow
  • Loading branch information
H1rono committed Jun 14, 2024
2 parents c97b85b + 07aeec6 commit f3bfde7
Show file tree
Hide file tree
Showing 7 changed files with 135 additions and 0 deletions.
41 changes: 41 additions & 0 deletions app/imshow/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
cmake_minimum_required(VERSION 3.8)
project(imshow)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(image_transport REQUIRED)
find_package(OpenCV REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

# Create executable
add_executable(imshow src/imshow.cpp src/main.cpp)
target_include_directories(imshow
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${OpenCV_INCLUDE_DIRS}
)

# Link dependencies
ament_target_dependencies(imshow rclcpp sensor_msgs cv_bridge image_transport)

target_link_libraries(imshow ${OpenCV_LIBRARIES})

# Install targets
install(TARGETS
imshow
DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME})

ament_package()
15 changes: 15 additions & 0 deletions app/imshow/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# imshow

USBカメラの映像を映す

## Nodes

- `Imshow`: 映像を映す

## Executables

- `imshow`: `imshow`Nodeをspin


## Launches

13 changes: 13 additions & 0 deletions app/imshow/include/imshow/imshow.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
#include <cv_bridge/cv_bridge.hpp>
#include <opencv2/opencv.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>

class Imshow : public rclcpp::Node {
public:
Imshow();

private:
void image_callback(const sensor_msgs::msg::Image::SharedPtr msg);
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscription_;
};
13 changes: 13 additions & 0 deletions app/imshow/launch/imshow_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():
return LaunchDescription([
Node(
package="imshow",
executable="imshow",
namespace="app",
remappings=[("/app/camera/image", "/packet/camera/image")]
)
])
23 changes: 23 additions & 0 deletions app/imshow/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>imshow</name>
<version>0.0.0</version>
<description>ROS 2 package for receiving images</description>
<maintainer email="[email protected]">hiro</maintainer>
<license>MIT License</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rclcpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>image_transport</build_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>cv_bridge</exec_depend>
<exec_depend>image_transport</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
20 changes: 20 additions & 0 deletions app/imshow/src/imshow.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#include "imshow/imshow.hpp"

Imshow::Imshow() : Node("imshow") {
subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
"camera/image",
10,
std::bind(&Imshow::image_callback, this, std::placeholders::_1)
);
}

void Imshow::image_callback(const sensor_msgs::msg::Image::SharedPtr msg) {
try {
const cv::Mat frame = cv_bridge::toCvCopy(msg, "bgr8")->image;
cv::imshow("Received Image", frame);
cv::waitKey(1);
} catch (const cv_bridge::Exception& e) {
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
return;
}
}
10 changes: 10 additions & 0 deletions app/imshow/src/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include "imshow/imshow.hpp"
#include <rclcpp/rclcpp.hpp>

int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
auto node = std::make_shared<Imshow>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

0 comments on commit f3bfde7

Please sign in to comment.