머신러닝

본문 바로가기
사이트 내 전체검색


머신러닝
머신러닝

8. 액션 메시지를 활용한 카메라 화면 캡쳐

페이지 정보

작성자 관리자 댓글 0건 조회 3,029회 작성일 21-01-15 16:44

본문

8. 액션 메시지를 활용한 카메라 화면 캡쳐

액션 메시지를 활용하여 카메라 화면 캡쳐하는 명령을 전달하여 지정한 시간 동안 이동하며 사진을 찍고 저장하는 실습을 진행해보도록 하겠습니다. 

액션은 지정한 시간 동안만 수행되며 사진을 촬영할 때 마다 피드백을 통해 사진 촬영 여부를 전달하도록 작성합니다. 

이제 패키지를 생성하고 프로그램을 작성합니다. 

패키지 생성은 앞서 액션 메시지 패키지 생성과 동일 합니다.


jklee@holdings:~/catkin_ws/src$ catkin_create_pkg camera_actions rospy std_msgs actionlib_msgs

Created file camera_actions/package.xml

Created file camera_actions/CMakeLists.txt

Created folder camera_actions/src

Successfully created files in /home/jklee/catkin_ws/src/camera_actions. Please adjust the values in package.xml.

jklee@holdings:~/catkin_ws/src$ cd camera_actions/

jklee@holdings:~/catkin_ws/src/camera_actions$



액션 메시지 등록을 위한 각종 소스코드와 내용들은 이 폴더에 작성합니다. 

폴더로 이동하고 첫번째로 어떠한 구조의 액션 메시지를 등록할 것인지 작성합니다. 

action 폴더를 생성하고 폴더 내부에 robot.action 파일을 생성하고 내용을 편집합니다.


jklee@holdings:~/catkin_ws/src/camera_actions$ mkdir action

jklee@holdings:~/catkin_ws/src/camera_actions$ vi action/robot.action

# Goal
uint32 seconds
---
# Result
string result_path
---
# Feedback
uint32 num_of_picture


robot.action 파일에 작성한 내용은 총 3 개의 변수의 내용을 담고 있습니다. 

액션의 목표에 해당하는 seconds 와 결과에 해당하는 result_path, 피드백에 해당하는 num_of_picture 입니다.


이제 실제로 액션 메시지 등록과 호출시 실행할 소스코드를 작성합니다. 

src 폴더에 action_server.py 를 작성합니다.



jklee@holdings:~/catkin_ws/src/camera_actions$ vi src/action_server.py


#! /usr/bin/env python3


import cv2

import os, time


import rospy

import actionlib


from pop import Camera

from pop.Pilot import AutoCar

from camera_actions.msg import *


class ActionServer():


    def __init__(self):

        self.bot = AutoCar()

        self.cam = Camera(640, 640)

        self.a_server = actionlib.SimpleActionServer("motor_control", robotAction, execute_cb=self.execute_cb, auto_start=False)


        self.a_server.start()


    def execute_cb(self, goal):

        count = 0

        success = True

        rate = rospy.Rate(5)

        result = robotResult()

        feedback = robotFeedback()


        path = time.strftime('/home/jklee/catkin_ws/%Y-%m-%d %H-%M-%S/', time.localtime(time.time()))

        os.mkdir(path)


        dtime = stime = time.time()

        while time.time() - stime < goal.seconds:

            if self.a_server.is_preempt_requested():

                success = False

                break


            self.bot.forward(30)


            filename = path + str(count) + '.jpg'

            cv2.imwrite(filename, self.cam.value)


            count += 1

            feedback.num_of_picture = count

            self.a_server.publish_feedback(feedback)


            rate.sleep()


        self.bot.stop()


        if success:

            result.result_path = path + "{}~{}.jpg".format(0, count-1)

            self.a_server.set_succeeded(result)


if __name__ == "__main__":

    rospy.init_node("Action_Server")

    s = ActionServer()


    rospy.spin()


기본적인 코드 구조는 앞서 작성한 액션 서버의 구조와 동일합니다. 

액션 명령이 전달되었을 때 로봇의 움직임과 카메라 촬영을 위한 내용을 pop 라이브러리에서 호출합니다. 

카메라 영상은 640x640 으로 촬영하도록 설정되어 있습니다. 

액션 호출이 이루어지면 전달된 시간과 각도 값을 이용하여 한방향으로 로봇을 움직이도록 제어합니다.


이동되는 동안 카메라 촬영을 시도하고 촬영이 될 때 피드백을 전달합니다. 

정상적으로 전달된 시간만큼 제어가 되면 로봇의 이동을 정지하고 결과를 전송합니다.


프로그램 작성을 완료하고 rosrun 을 통해 실행될 수 있도록 작성한 소스코드에 실행권한을 부여합니다.



jklee@holdings:~/catkin_ws/src/camera_actions$ chmod +x src/action_server.py



이제 컴파일을 위한 CMakeLists.txt 파일과 package.xml 파일을 수정합니다.

CMakeLists.txt 에는 컴파일 옵션들을 지정합니다. 

기본적인 내용은 패키지 생성시 미리 작성되어 있습니다. 

서비스 등록을 위한 내용을 추가합니다.


jklee@holdings:~/catkin_ws/src/camera_actions$ vi CMakeLists.txt


### 생략

find_package(catkin REQUIRED COMPONENTS

  actionlib_msgs

  rospy

  std_msgs

  message_generation

)

### 생략

add_action_files(

   FILES

   robot.action

)

### 생략

generate_messages(

   DEPENDENCIES

   actionlib_msgs

   std_msgs 

)

### 생략


package.xml 파일에는 컴파일 할 때 참조하는 패키지나 실행할 때 참조하는 내용을 입력합니다. 

package.xml 도 CMakeLists.txt 파일과 마찬가지로 패키지 생성시 기본적인 내용은 작성되어 있는상태로 필요한 내용만 추가하거나 주석을 제거하면 됩니다.


jklee@holdings:~/catkin_ws/src/camera_actions$ vi package.xml


<!-- 생략 -->

<build_depend>message_generation</build_depend>

<!-- 생략 -->

<exec_depend>message_runtime</exec_depend>

<!-- 생략 -->


작성한 액션을 통해 명령을 내리고 결과를 수신하는 클라이언트를 작성합니다. 

서버와 마찬가지로 src 폴더에 프로그램을 작성합니다.


jklee@holdings:~/catkin_ws/src/camera_actions$ vi src/action_client.py

#! /usr/bin/env python3

import rospy
import actionlib
from camera_actions.msg import *

def feedback_cb(msg):
    print("Feedback: ", msg)

def call_server(arg):
    client = actionlib.SimpleActionClient('motor_control', robotAction)
    client.wait_for_server()
    goal = robotGoal()
    goal.seconds = arg[0]
    client.send_goal(goal, feedback_cb=feedback_cb)
    client.wait_for_result()

    result = client.get_result()
    return result

if __name__ == "__main__":
    rospy.init_node("Action_Client")
    arg = [0] * 1
    arg[0] = int(input("Second: "))
    print("Result is ", call_server(arg))


프로그램을 실행하면 액션 메시지로 전달할 로봇 제어 시간을 지정합니다. 

시간은 초단위입니다. 

사용자 입력을 받고나면 실행중인 ROS 에 등록되어 있는 액션 메시지를 찾아 호출합니다. 

호출되어 동작되는 동안의 피드백은 화면에 출력하도록 피드백 콜백 메소드를 등록하고 결과가 도착할 때까지 대기합니다. 

동작이 완료되고 결과를 수신하면 수신된 결과를 화면에 출력합니다.


프로그램 작성을 완료하고 rosrun 을 통해 실행될 수 있도록 작성한 소스코드에 실행권한을 부여합니다.


jklee@holdings:~/catkin_ws/src/camera_actions$ chmod +x src/action_client.py


컴파일 및 실행을 위한 파일 수정은 완료되었습니다. 

catkin_make 명령을 통해 컴파일을 실행합니다. 

컴파일이 완료되고 나면 완료된 내용을 현재 사용중인 쉘에 적용해야 합니다. 

devel 폴더의 setup.bash 파일을 source 명령을 통해 적용합니다.


jklee@holdings:~/catkin_ws/src/camera_actions$ cd ~/catkin_ws

jklee@holdings:~/catkin_ws$ catkin_make

Base path: /home/jklee/catkin_ws

Source space: /home/jklee/catkin_ws/src

Build space: /home/jklee/catkin_ws/build

Devel space: /home/jklee/catkin_ws/devel

Install space: /home/jklee/catkin_ws/install

####

#### Running command: "cmake /home/jklee/catkin_ws/src -DCATKIN_DEVEL_PREFIX=/home/jklee/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/home/jklee/catkin_ws/install -G Unix Makefiles" in "/home/jklee/catkin_ws/build"

####

-- Using CATKIN_DEVEL_PREFIX: /home/jklee/catkin_ws/devel

-- Using CMAKE_PREFIX_PATH: /home/jklee/catkin_ws/devel;/opt/ros/melodic

-- This workspace overlays: /home/jklee/catkin_ws/devel;/opt/ros/melodic

-- Found PythonInterp: /usr/bin/python2 (found suitable version "2.7.17", minimum required is "2")

-- Using PYTHON_EXECUTABLE: /usr/bin/python2

-- Using Debian Python package layout

-- Using empy: /usr/bin/empy

-- Using CATKIN_ENABLE_TESTING: ON

-- Call enable_testing()

-- Using CATKIN_TEST_RESULTS_DIR: /home/jklee/catkin_ws/build/test_results

-- Found gtest sources under '/usr/src/googletest': gtests will be built

-- Found gmock sources under '/usr/src/googletest': gmock will be built

-- Found PythonInterp: /usr/bin/python2 (found version "2.7.17")

-- Using Python nosetests: /usr/bin/nosetests-2.7

-- catkin 0.7.28

-- BUILD_SHARED_LIBS is on

-- BUILD_SHARED_LIBS is on

-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

-- ~~  traversing 4 packages in topological order:

-- ~~  - actions_tutorial

-- ~~  - camera_actions

-- ~~  - motor_service

-- ~~  - service_tutorial

-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

-- +++ processing catkin package: 'actions_tutorial'

-- ==> add_subdirectory(actions_tutorial)

-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- Generating .msg files for action actions_tutorial/WashTheDishes /home/jklee/catkin_ws/src/actions_tutorial/action/WashTheDishes.action

-- actions_tutorial: 7 messages, 0 services

-- +++ processing catkin package: 'camera_actions'

-- ==> add_subdirectory(camera_actions)

-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- Generating .msg files for action camera_actions/robot /home/jklee/catkin_ws/src/camera_actions/action/robot.action

Generating for action robot

-- camera_actions: 7 messages, 0 services

-- +++ processing catkin package: 'motor_service'

-- ==> add_subdirectory(motor_service)

-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- motor_service: 0 messages, 1 services

-- +++ processing catkin package: 'service_tutorial'

-- ==> add_subdirectory(service_tutorial)

-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy

-- service_tutorial: 0 messages, 1 services

-- Configuring done

-- Generating done

-- Build files have been written to: /home/jklee/catkin_ws/build

####

#### Running command: "make -j4 -l4" in "/home/jklee/catkin_ws/build"

####

[  0%] Built target actionlib_msgs_generate_messages_eus

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesActionFeedback

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesResult

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesGoal

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesAction

[  0%] Built target std_msgs_generate_messages_eus

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesFeedback

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesActionGoal

[  0%] Built target _actions_tutorial_generate_messages_check_deps_WashTheDishesActionResult

[  0%] Built target actionlib_msgs_generate_messages_py

[  0%] Built target actionlib_msgs_generate_messages_nodejs

[  0%] Built target std_msgs_generate_messages_py

[  0%] Built target std_msgs_generate_messages_nodejs

[  0%] Built target std_msgs_generate_messages_lisp

[  0%] Built target actionlib_msgs_generate_messages_lisp

[  0%] Built target actionlib_msgs_generate_messages_cpp

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotAction

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotActionResult

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotResult

[  0%] Built target std_msgs_generate_messages_cpp

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotActionFeedback

[  0%] Built target _camera_actions_generate_messages_check_deps_robotAction

[  0%] Built target _camera_actions_generate_messages_check_deps_robotActionResult

[  0%] Built target _camera_actions_generate_messages_check_deps_robotResult

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotFeedback

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotGoal

[  0%] Built target _camera_actions_generate_messages_check_deps_robotActionFeedback

Scanning dependencies of target _camera_actions_generate_messages_check_deps_robotActionGoal

[  0%] Built target _camera_actions_generate_messages_check_deps_robotFeedback

[  0%] Built target _camera_actions_generate_messages_check_deps_robotActionGoal

[  0%] Built target _camera_actions_generate_messages_check_deps_robotGoal

[  0%] Built target _motor_service_generate_messages_check_deps_motor

[  9%] Built target actions_tutorial_generate_messages_eus

[ 18%] Built target actions_tutorial_generate_messages_py

[ 26%] Built target actions_tutorial_generate_messages_nodejs

[ 34%] Built target actions_tutorial_generate_messages_lisp

[ 34%] Built target _service_tutorial_generate_messages_check_deps_AddInts

[ 42%] Built target actions_tutorial_generate_messages_cpp

Scanning dependencies of target camera_actions_generate_messages_lisp

Scanning dependencies of target camera_actions_generate_messages_eus

Scanning dependencies of target camera_actions_generate_messages_nodejs

Scanning dependencies of target camera_actions_generate_messages_cpp

[ 43%] Generating Lisp code from camera_actions/robotActionResult.msg

[ 44%] Generating EusLisp code from camera_actions/robotActionResult.msg

[ 45%] Generating C++ code from camera_actions/robotActionResult.msg

[ 46%] Generating Javascript code from camera_actions/robotActionResult.msg

[ 47%] Generating Lisp code from camera_actions/robotFeedback.msg

[ 48%] Generating Javascript code from camera_actions/robotFeedback.msg

[ 50%] Generating EusLisp code from camera_actions/robotFeedback.msg

[ 51%] Generating Lisp code from camera_actions/robotGoal.msg

[ 52%] Generating Javascript code from camera_actions/robotGoal.msg

[ 53%] Generating Lisp code from camera_actions/robotActionGoal.msg

[ 54%] Generating Javascript code from camera_actions/robotActionGoal.msg

[ 55%] Generating EusLisp code from camera_actions/robotGoal.msg

[ 56%] Generating C++ code from camera_actions/robotFeedback.msg

[ 57%] Generating Lisp code from camera_actions/robotResult.msg

[ 59%] Generating Javascript code from camera_actions/robotResult.msg

[ 60%] Generating EusLisp code from camera_actions/robotActionGoal.msg

[ 61%] Generating Lisp code from camera_actions/robotAction.msg

[ 62%] Generating Javascript code from camera_actions/robotAction.msg

[ 63%] Generating Lisp code from camera_actions/robotActionFeedback.msg

[ 64%] Generating Javascript code from camera_actions/robotActionFeedback.msg

[ 65%] Generating EusLisp code from camera_actions/robotResult.msg

[ 65%] Built target camera_actions_generate_messages_lisp

[ 65%] Built target camera_actions_generate_messages_nodejs

[ 67%] Generating EusLisp code from camera_actions/robotAction.msg

[ 68%] Generating EusLisp code from camera_actions/robotActionFeedback.msg

[ 69%] Generating C++ code from camera_actions/robotGoal.msg

[ 70%] Generating EusLisp manifest code for camera_actions

[ 71%] Generating C++ code from camera_actions/robotActionGoal.msg

Scanning dependencies of target camera_actions_generate_messages_py

[ 72%] Generating Python from MSG camera_actions/robotActionResult

[ 73%] Generating Python from MSG camera_actions/robotFeedback

[ 75%] Generating C++ code from camera_actions/robotResult.msg

[ 76%] Generating C++ code from camera_actions/robotAction.msg

[ 77%] Generating Python from MSG camera_actions/robotGoal

[ 78%] Generating C++ code from camera_actions/robotActionFeedback.msg

[ 79%] Generating Python from MSG camera_actions/robotActionGoal

[ 80%] Generating Python from MSG camera_actions/robotResult

[ 81%] Generating Python from MSG camera_actions/robotAction

[ 82%] Generating Python from MSG camera_actions/robotActionFeedback

[ 82%] Built target camera_actions_generate_messages_cpp

[ 85%] Built target motor_service_generate_messages_py

[ 87%] Built target motor_service_generate_messages_eus

[ 88%] Built target motor_service_generate_messages_lisp

[ 89%] Generating Python msg __init__.py for camera_actions

[ 90%] Built target motor_service_generate_messages_cpp

[ 92%] Built target motor_service_generate_messages_nodejs

[ 93%] Built target service_tutorial_generate_messages_lisp

[ 95%] Built target service_tutorial_generate_messages_eus

[ 95%] Built target camera_actions_generate_messages_eus

[ 96%] Built target service_tutorial_generate_messages_cpp

[ 98%] Built target service_tutorial_generate_messages_py

[100%] Built target service_tutorial_generate_messages_nodejs

[100%] Built target actions_tutorial_generate_messages

[100%] Built target motor_service_generate_messages

[100%] Built target service_tutorial_generate_messages

[100%] Built target camera_actions_generate_messages_py

Scanning dependencies of target camera_actions_generate_messages

[100%] Built target camera_actions_generate_messages

jklee@holdings:~/catkin_ws$



jklee@holdings:~/catkin_ws$ source devel/setup.bash



이제 프로그램 실행을 위해 새로운 터미널에서 마스터노드를 실행합니다. 

마스터 노드 실행 명령은 roscore 입니다.


jklee@holdings:~$ roscore

... logging to /home/jklee/.ros/log/fde7ea16-5932-11eb-be2e-000000000001/roslaunch-holdings-31777.log

Checking log directory for disk usage. This may take a while.

Press Ctrl-C to interrupt

Done checking log file disk usage. Usage is <1GB.


started roslaunch server http://localhost:35343/

ros_comm version 1.14.7



SUMMARY

========


PARAMETERS

 * /rosdistro: melodic

 * /rosversion: 1.14.7


NODES


auto-starting new master

process[master]: started with pid [31790]

ROS_MASTER_URI=http://localhost:11311/


setting /run_id to fde7ea16-5932-11eb-be2e-000000000001

process[rosout-1]: started with pid [31804]

started core service [/rosout]



세로 작성한 노드는 마스터 노드가 실행되어 있지 않다면 정상적으로 실행되지 않습니다. 

마스터 노드 실행된 이후에 마스터노드가 실행되지 않은 터미널에서 rosrun 명령을 통해 컴파일한 패키지를 실행합니다.



jklee@holdings:~/catkin_ws$ rosrun camera_actions action_server.py

[sudo] password for jklee: Sorry, try again.
[sudo] password for jklee:
sudo: 1 incorrect password attempt
GST_ARGUS: Creating output stream
CONSUMER: Waiting until producer is connected...
GST_ARGUS: Available Sensor modes :
GST_ARGUS: 3264 x 2464 FR = 21.000000 fps Duration = 47619048 ; Analog Gain range min 1.000000, max 10.625000; Exposure Range min 13000, max 683709000;

GST_ARGUS: 3264 x 1848 FR = 28.000001 fps Duration = 35714284 ; Analog Gain range min 1.000000, max 10.625000; Exposure Range min 13000, max 683709000;

GST_ARGUS: 1920 x 1080 FR = 29.999999 fps Duration = 33333334 ; Analog Gain range min 1.000000, max 10.625000; Exposure Range min 13000, max 683709000;

GST_ARGUS: 1280 x 720 FR = 59.999999 fps Duration = 16666667 ; Analog Gain range min 1.000000, max 10.625000; Exposure Range min 13000, max 683709000;

GST_ARGUS: 1280 x 720 FR = 120.000005 fps Duration = 8333333 ; Analog Gain range min 1.000000, max 10.625000; Exposure Range min 13000, max 683709000;

GST_ARGUS: Running with following settings:
   Camera index = 0
   Camera mode  = 0
   Output Stream W = 3264 H = 2464
   seconds to Run    = 0
   Frame Rate = 21.000000
GST_ARGUS: PowerService: requested_clock_Hz=37126320
GST_ARGUS: Setup Complete, Starting captures for 0 seconds
GST_ARGUS: Starting repeat capture requests.
CONSUMER: Producer has connected; continuing.
[ WARN:0] global /home/soda/opencv/modules/videoio/src/cap_gstreamer.cpp (935) open OpenCV | GStreamer warning: Cannot query video position: status=0, value=-1, duration=-1


다른 터미널에서 메세지를 확인할 수 있다.


jklee@proportionately:~/catkin_ws$ rosmsg list | grep camera

camera_actions/robotAction

camera_actions/robotActionFeedback

camera_actions/robotActionGoal

camera_actions/robotActionResult

camera_actions/robotFeedback

camera_actions/robotGoal

camera_actions/robotResult

jklee@proportionately:~/catkin_ws$



프로그램 작성이 완료되면 rosrun 명령을 통해 클라이언트를 실행합니다.


rosrun camera_actions action_client.py

Second: 3

Feedback:  num_of_picture: 1

Feedback:  num_of_picture: 2

Feedback:  num_of_picture: 3

Feedback:  num_of_picture: 4

Feedback:  num_of_picture: 5

Feedback:  num_of_picture: 6

Feedback:  num_of_picture: 7

Feedback:  num_of_picture: 8

Feedback:  num_of_picture: 9

Feedback:  num_of_picture: 10

Feedback:  num_of_picture: 11

Feedback:  num_of_picture: 12

Feedback:  num_of_picture: 13

Feedback:  num_of_picture: 14

Feedback:  num_of_picture: 15

Result is  result_path: "/home/jklee/catkin_ws/2021-02-14 13-33-41/0~14.jpg"

jklee@sinks:~/catkin_ws$ ls
'2021-02-14 13-33-41'   build   devel   src   ws.log
jklee@sinks:~/catkin_ws$ ls 2021-02-14\ 13-33-41/
0.jpg   11.jpg  13.jpg  1.jpg  3.jpg  5.jpg  7.jpg  9.jpg
10.jpg  12.jpg  14.jpg  2.jpg  4.jpg  6.jpg  8.jpg
jklee@sinks:~/catkin_ws$


댓글목록

등록된 댓글이 없습니다.


개인정보취급방침 서비스이용약관 모바일 버전으로 보기 상단으로

TEL. 063-469-4551 FAX. 063-469-4560 전북 군산시 대학로 558
군산대학교 컴퓨터정보공학과

Copyright © www.leelab.co.kr. All rights reserved.