๋ณธ๋ฌธ ๋ฐ”๋กœ๊ฐ€๊ธฐ

์นดํ…Œ๊ณ ๋ฆฌ ์—†์Œ

25. [ROS RC์นด] Object Following - 3 & ๊ฐ•์˜ ๋งˆ๋ฌด๋ฆฌ์™€ Future Work ์†Œ๊ฐœ

๐Ÿ‘๐Ÿป

25. [ROS RC์นด] Object Following - 3 & ๊ฐ•์˜ ๋งˆ๋ฌด๋ฆฌ์™€ Future Work ์†Œ๊ฐœ

๐ŸŽ‡ ์ง€๋‚œ ์‹œ๊ฐ„์— ์ด์–ด์„œ, find_ball node๋ฅผ ๋ถ„์„ํ•ด ๋ณด๊ฒ ์Šต๋‹ˆ๋‹ค. ๐ŸŽ‡

  • ๊ทธ๋Ÿผ ์ด๋ฒˆ์—”, main๋ฌธ์— ์žˆ๋Š” ์ด ์ˆ˜๋งŽ์€ ์ฝ”๋“œ๋“ค์€ ๋ฌด์—‡์ผ๊นŒ์š”?
    params = cv2.SimpleBlobDetector_Params()

    # Change thresholds
    params.minThreshold = 0
    params.maxThreshold = 200

    # Filter by Area.
    params.filterByArea = True
    params.minArea = 2000
    params.maxArea = 70000  # 640 * 480 = 307,200

    # Filter by Circularity
    params.filterByCircularity = True
    params.minCircularity = 0.1

    # Filter by Convexity
    params.filterByConvexity = True
    params.minConvexity = 0.2

    # Filter by Inertia
    params.filterByInertia = True
    params.minInertiaRatio = 0.7

    rospy.init_node("blob_detector", anonymous=True)
    ic = BlobDetector(green_min, green_max, blur, params, detection_window)
  • ๋ฌผ์ฒด๋กœ ์ธ์‹๋˜๊ธฐ ์œ„ํ•ด์„œ๋Š” ์ตœ์†Œ, ์ตœ๋Œ€ ์–ด๋Š์ •๋„ ํ”ฝ์…€ ๋ฉด์ ์„ ๊ฐ€์ ธ์•ผ ํ•˜๋Š”์ง€,
  • ์‚ฌ๊ฐํ˜• ๋ฌผ์ฒด, ์›ํ˜• ๋ฌผ์ฒด๋งŒ ์ธ์‹ํ•  ๊ฒƒ์ธ์ง€,
  • ์–ผ๋งˆ๋‚˜ ํ•„ํ„ฐ์— ์ ํ•ฉํ•ด์•ผ ๋ฌผ์ฒด๋กœ ์ธ์‹ํ•  ๊ฒƒ์ธ์ง€ ๋“ฑ์˜ ๋งค๊ฐœ๋ณ€์ˆ˜๋ฅผ ์„ค์ •ํ•˜๋Š” ๋ถ€๋ถ„์ž…๋‹ˆ๋‹ค.

  • ๊ฐ ๋งค๊ฐœ๋ณ€์ˆ˜๋“ค์— ๋Œ€ํ•œ ์ž์„ธํ•œ ์„ค๋ช…์€ ๋ ˆํผ๋Ÿฐ์Šค๋ฅผ ๋‚จ๊ธฐ๊ฒ ์Šต๋‹ˆ๋‹ค.
Blob Detection Using OpenCV ( Python, C++ )
This tutorial explains simple blob detection using OpenCV. What is a Blob? A Blob is a group of connected pixels in an image that share some common property ( E.g grayscale value ). In the image above, the dark connected regions are blobs, and the goal of blob detection is to identify and mark these [...]
https://learnopencv.com/blob-detection-using-opencv-python-c/

์ด ๋งค๊ฐœ๋ณ€์ˆ˜๋“ค์„, cv2.SimpleBlobDetector_create์—๊ฒŒ ๋„˜๊ฒจ์ฃผ๋ฉด, ํ”ฝ์…€ ์—ฐ์‚ฐ์„ ๊ฑฐ์ณ keypoints(ํŠน์ง•์ )๋ฅผ ๋ฐ˜ํ™˜ํ•ฉ๋‹ˆ๋‹ค. ์ด ํŠน์ง•์ ์ด ๋ฐ”๋กœ ์šฐ๋ฆฌ๊ฐ€ ์ถ”์ ํ•˜๊ณ ์ž ํ•˜๋Š” ๋ฌผ์ฒด์˜ ์ด๋ฏธ์ง€์ƒ์—์„œ ์œ„์น˜๊ฐ€ ๋˜์ง€์š”.

  • blob_detector
		#- Apply blob detection
    detector = cv2.SimpleBlobDetector_create(params)

    # Reverse the mask: blobs are black on white
    reversemask = 255-mask
    
    if imshow:
        cv2.imshow("Reverse Mask", reversemask)
        cv2.waitKey(0)
        
    keypoints = detector.detect(reversemask)

    return keypoints, reversemask

image_blob ํ† ํ”ฝ์ž…๋‹ˆ๋‹ค.

  • ๋ฌผ์ฒด๋กœ ์ธ์‹๋˜์—ˆ๋‹ค๋ฉด, ์‚ฌ์ง„๊ณผ ๊ฐ™์ด ๋นจ๊ฐ„ ๋™๊ทธ๋ผ๋ฏธ๊ฐ€ ์ƒ๊ธฐ๋Š” ๊ฒƒ์ด ๋ณด์ด๋ฉฐ,
  • ํŒŒ๋ž€ ์‚ฌ๊ฐํ˜• ๋ฐ”๊นฅ ๋ถ€๋ถ„์€ ํ๋ฆฌ๊ฒŒ ์ฒ˜๋ฆฌ๋˜์—ˆ์ง€์š”?

์—ฐ์‚ฐ๋Ÿ‰์„ ์ค„์ด๊ธฐ ์œ„ํ•ด, ๊ทธ๋ฆฌ๊ณ  ์™ธ๊ณก์ด ์‹ฌํ•œ ํ…Œ๋‘๋ฆฌ ๋ถ€๋ถ„์—์„œ์˜ ์˜ค์ฐจ๋ฅผ ๋ฐฉ์ง€ํ•˜๊ธฐ ์œ„ํ•œ ์ฒ˜๋ฆฌ์ž…๋‹ˆ๋‹ค.

์‹ค์ œ ์ฝ”๋“œ์—์„œ๋Š” ์–ด๋–ป๊ฒŒ ๊ตฌํ˜„๋˜์–ด ์žˆ๋Š”์ง€ ์‚ดํŽด๋ณด๊ฒ ์Šต๋‹ˆ๋‹ค.

  • find_ball.py
draw_keypoints#--- Detect blobs
keypoints, mask   = blob_detect(cv_image, self._threshold[0], self._threshold[1], self._blur,
                                blob_params=self._blob_params, search_window=self.detection_window )
#--- Draw search window and blobs
cv_image    = blur_outside(cv_image, 10, self.detection_window)

cv_image    = draw_window(cv_image, self.detection_window, line=1)
cv_image    = draw_frame(cv_image)

cv_image    = draw_keypoints(cv_image, keypoints) 

try:
    self.image_pub.publish(self.bridge.cv2_to_imgmsg(cv_image, "bgr8"))
    self.mask_pub.publish(self.bridge.cv2_to_imgmsg(mask, "8UC1"))
  • draw_window : ๊ด€์‹ฌ ์ง€์—ญ์ธ ํŒŒ๋ž€ ์‚ฌ๊ฐํ˜•์„ ๊ทธ๋ ค์ค๋‹ˆ๋‹ค. ์‚ฌ๊ฐํ˜•์˜ ํฌ๊ธฐ๋Š” main์— ๋น„์œจ ํ˜•ํƒœ์˜ ๋งค๊ฐœ๋ณ€์ˆ˜๋ฅผ ์‚ฌ์šฉํ•ฉ๋‹ˆ๋‹ค.
  • blur_outside : ํŒŒ๋ž€ ์‚ฌ๊ฐํ˜• ๋ฐ”๊นฅ ๋ถ€๋ถ„์€ ํ๋ฆผ ์ฒ˜๋ฆฌ๋ฅผ ํ•ด์ค๋‹ˆ๋‹ค.
  • draw_frame : ์ด๋ฏธ์ง€ ์ค‘์‹ฌ์— ์นด๋ฉ”๋ผ ํ”„๋ ˆ์ž„์„ ๊ทธ๋ ค์ค๋‹ˆ๋‹ค.
  • draw_keypoints : ์ตœ์ข…์ ์œผ๋กœ, ์šฐ๋ฆฌ๊ฐ€ ์ถ”์ ํ•˜๊ณ ์ž ํ•˜๋Š” keypoints๋ฅผ ๋นจ๊ฐ„ ๋™๊ทธ๋ผ๋ฏธ๋กœ ํ‘œ์‹œํ•ด์ค๋‹ˆ๋‹ค.

๊ฐ ํ•จ์ˆ˜๋“ค์— ๋Œ€ํ•ด์„œ๋Š” include/blob_detector.py๋ฅผ ์ฐธ์กฐํ•˜์‹œ๊ธธ ๋ฐ”๋ž๋‹ˆ๋‹ค.

๋Œ€๋ง์˜ publish


for i, keyPoint in enumerate(keypoints):
    #--- Here you can implement some tracking algorithm to filter multiple detections
    #--- We are simply getting the first result
    x = keyPoint.pt[0]
    y = keyPoint.pt[1]
    s = keyPoint.size
    print ("kp %d: s = %3d   x = %3d  y= %3d"%(i, s, x, y))
    
    #--- Find x and y position in camera adimensional frame
    x, y = get_blob_relative_position(cv_image, keyPoint)
    
    self.blob_point.x = x
    self.blob_point.y = y
    self.blob_pub.publish(self.blob_point) 
    break

๊ทธ๋Ÿผ ์ตœ์ข…์ ์œผ๋กœ ๋‹ค์Œ node์— publish๋˜๋Š” ๊ฐ’์€ ๋ฌด์—‡์ผ๊นŒ์š”??

์—ฌ๋Ÿฌ ๋ฌผ์ฒด๊ฐ€ ์žˆ๋Š” ๊ฒฝ์šฐ์— ๋Œ€๋น„ํ•œ ์ฝ”๋“œ๊ฐ€ ๋ณด์ด๋ฉฐ, get_blob_relative_position๋กœ๋ถ€ํ„ฐ์˜ output์„ ์‚ฌ์šฉํ•˜๊ณ  ์žˆ์Šต๋‹ˆ๋‹ค. ์ด ํ•จ์ˆ˜๋ฅผ ์‚ดํŽด์•ผ๊ฒ ์ง€์š”.

  • get_blob_relative_position
#---------- Obtain the camera relative frame coordinate of one single keypoint
#-- return(x,y)
def get_blob_relative_position(image, keyPoint):
    cols = float(image.shape[0]) # 480
    rows = float(image.shape[1]) # 640
    # print(rows, cols)
    center_x    = 0.5*rows # 320
    center_y    = 0.5*cols # 240
    # print(center_x)
    x = (keyPoint.pt[0] - center_x)/(center_x)
    y = (keyPoint.pt[1] - center_y)/(center_y)
    return(x,y)

์Œ... ์ž˜ ์™€๋‹ฟ์ง€ ์•Š์ง€์š”? ์˜ˆ์‹œ๋ฅผ ํ†ตํ•ด ์‚ดํŽด๋ณด๊ฒ ์Šต๋‹ˆ๋‹ค.

ํ˜„์žฌ ์šฐ๋ฆฌ๊ฐ€ ์‚ฌ์šฉ์ค‘์ธ ์ด๋ฏธ์ง€๋Š” [640 * 480]์˜ ํฌ๊ธฐ๋ฅผ ๊ฐ–์Šต๋‹ˆ๋‹ค.

๋ž˜์„œ ์ค‘์‹ฌ ํ”ฝ์…€์€ [320, 240]์˜ ์œ„์น˜๋ฅผ ๊ฐ–์Šต๋‹ˆ๋‹ค.

์ด ์ƒํ™ฉ์—์„œ, keypoint์˜ ์œ„์น˜๊ฐ€ [370, 240]์ด๋ผ๊ณ  ํ•œ๋‹ค๋ฉด

โ‡’ x = (keyPoint.pt[0] - center_x)/(center_x)

โ‡’ x = (370 - 320) / 320

์ด๋ ‡๊ฒŒ ๊ณ„์‚ฐํ•  ์ˆ˜ ์žˆ์Šต๋‹ˆ๋‹ค.

์ฆ‰, publish๋˜๋Š” blob_point.x, blob_point.y๋Š” ์ค‘์‹ฌ์œผ๋กœ๋ถ€ํ„ฐ keypoint๊ฐ€ ์–ด๋Š์ •๋„ ๋–จ์–ด์ ธ ์žˆ๋Š”์ง€๋ฅผ -1 ~ 1 ์‚ฌ์ด์˜ ๊ฐ’์œผ๋กœ ๋ณ€ํ™˜์‹œํ‚จ ๊ฒฐ๊ณผ๋ผ๊ณ  ํ•  ์ˆ˜ ์žˆ์Šต๋‹ˆ๋‹ค.

  • ๋‹ค์‹œ ํฐ๊ทธ๋ฆผ์„ ์‚ดํŽด๋ณด๊ฒ ์Šต๋‹ˆ๋‹ค.

  • csi_pub : ์นด๋ฉ”๋ผ ์ด๋ฏธ์ง€๋ฅผ ์†ก์ถœํ•ด์ฃผ๋Š” ๋…ธ๋“œ
  • blob_detector : ์ปดํ“จํ„ฐ ๋น„์ „์ด ์ ์šฉ๋œ ๋…ธ๋“œ, ๋…น์ƒ‰ ๋ฌผ์ฒด๋ฅผ ์ฐพ์•„๋‚ด๊ณ , ์ง€์†์ ์œผ๋กœ ์ถ”์ 
  • chase_ball : blob_point.x, blob_point.y๋ฅผ ์ œ์–ด๊ฐ’์ธ Twist ํ˜•์‹์œผ๋กœ ๋ณ€ํ™˜
  • image_view : ์ด๋ฏธ์ง€ ํ† ํ”ฝ ๋ทฐ์–ด
  • blob_chase_node : ์‹ค์งˆ์ ์ธ PWM ์ œ์–ด

๊ธธ๊ณ  ๊ธธ์—ˆ์Šต๋‹ˆ๋‹ค, ์—ฌ๊ธฐ๊นŒ์ง€ ๋”ฐ๋ผ์™€์ฃผ์‹  ์—ฌ๋Ÿฌ๋ถ„๋“ค ๋ชจ๋‘ ๊ณ ์ƒ ๋งŽ์œผ์…จ์Šต๋‹ˆ๋‹ค. ๐Ÿ‘

์ง€๊ธˆ๊นŒ์ง€ ์šฐ๋ฆฌ๊ฐ€ ๋ฐฐ์šด ๊ฒƒ


๊ธฐ์ดˆ ์ด๋ก ๋ถ€ํ„ฐ ์‹œ๋ฎฌ๋ ˆ์ด์…˜, ๊ทธ๋ฆฌ๊ณ  ์‹ค์ œ ํ•˜๋“œ์›จ์–ด ํ”„๋กœ์ ํŠธ๊นŒ์ง€!! ์ •๋ง ๋งŽ์€ ๊ฒƒ๋“ค์„ ์‚ดํŽด๋ณด์•˜์Šต๋‹ˆ๋‹ค.

์ด ๊ฐ•์˜๋ฅผ ์ž˜ ์ดํ•ดํ•˜์…จ๋‹ค๋ฉด, ์ด์ œ ROS๋ฅผ ์‚ฌ์šฉํ•  ์ค„ ์•ˆ๋‹ค๊ณ  ๋งํ•  ์ˆ˜ ์žˆ์„ ๊ฒƒ์ž…๋‹ˆ๋‹ค. ๐Ÿค–

โ›”์ฝ”๋“œ์ƒ์˜ ๋ฌธ์ œ๊ฐ€ ์ƒ๊ฒผ๋‹ค๋ฉดโ›”


Road-Balance/donkey_ros
donkey car with ROS!! Contribute to Road-Balance/donkey_ros development by creating an account on GitHub.
https://github.com/Road-Balance/donkey_ros
Road-Balance/gcamp_ros_basic
Contribute to Road-Balance/gcamp_ros_basic development by creating an account on GitHub.
https://github.com/Road-Balance/gcamp_ros_basic

  • ๋ฒ„๊ทธ, ์—๋Ÿฌ์˜ ๊ฒฝ์šฐ ์—ฌ๋Ÿฌ๋ถ„์˜ ๊ฐœ๋ฐœ ํ™˜๊ฒฝ๊ณผ ํ•จ๊ป˜ ๋ฌธ์ œ๊ฐ€ ๋œ ์ƒํ™ฉ์„ ์ตœ๋Œ€ํ•œ ์ž์„ธํžˆ ์•Œ๋ ค์ฃผ์„ธ์š”!!
  • ํ˜น์‹œ ๋‹ค๋ฅธ ์‚ฌ๋žŒ๋„ ์ด๋Ÿฐ ๋ฌธ์ œ๊ฐ€ ๋ฐœ์ƒํ–ˆ๋‚˜? ๊ณต์œ ํ•˜๊ณ , ํ•จ๊ป˜ ๋ฌธ์ œ๋ฅผ ํ•ด๊ฒฐํ•˜๊ณ  ์‹ถ๋‹ค๋ฉด, Discussion์„ ์‚ฌ์šฉํ•ด ์ฃผ์„ธ์š”.
  • ๋‹ค๊ฐ™์ด ๋””๋ฒ„๊น…์„ ํ•ด๋ด๋„ ๋„์ €ํžˆ ๋ชจ๋ฅด๊ฒ ๋‹ค. ๋„์™€์ฃผ์„ธ์š”!! โ‡’ Issues

    โ‡’ ๋งˆ์ฐฌ๊ฐ€์ง€๋กœ ๊ฐœ๋ฐœํ™˜๊ฒฝ, ์ตœ๋Œ€ํ•œ ์ž์„ธํžˆ!!!

๋‹ค์Œ์œผ๋กœ, ๋ญ˜ ํ•ด๋ณผ๊นŒ์š”?
  • Robotics Roadmap
mithi/robotics-coursework
If you want to use Arduino or Raspberry Pi to make robots, this short list might be helpful. Check this short list if you like reading textbooks. Here are some pending links that might be someday be transfered in this document.
https://github.com/mithi/robotics-coursework/#hands-on-and-blogs
  • ROS2
ROS 2 Overview
The Robot Operating System (ROS) is a set of software libraries and tools for building robot applications. From drivers to state-of-the-art algorithms, and with powerful developer tools, ROS has what you need for your next robotics project. And it's all open source. Since ROS was started in 2007, a lot has changed in the robotics and ROS community.
https://index.ros.org/doc/ros2/
  • Navigation Stack
Wiki
Available Translations: SimpleChinese The Navigation Stack is fairly simple on a conceptual level. It takes in information from odometry and sensor streams and outputs velocity commands to send to a mobile base. Use of the Navigation Stack on an arbitrary robot, however, is a bit more complicated.
http://wiki.ros.org/navigation
  • Moveit
MoveIt Tutorials - moveit_tutorials Noetic documentation
Major contributors to the MoveIt tutorials are listed in chronological order: Sachin Chitta, Dave Hershberger, Acorn Pooley, Dave Coleman, Michael Gorner, Francisco Suarez, Mike Lautman. Help us improve these docs and we'll be happy to include you here also!
https://ros-planning.github.io/moveit_tutorials/
  • rosserial_arduino
Wiki
See also rosserial/Overview. SRF08 Ultrasonic Ranger In this tutorial, we will use an Arduino and a SRF08 Ultrasonic Ranger as a Range Finder.The SRF08 communicates with an Arduino over SPI/I2C. Advanced Configuration for NodeHandle and ArduinoHardware. This tutorial shows step by step how to configure NodeHandle and ArduinoHareware to better suit user needs.
http://wiki.ros.org/rosserial_arduino/Tutorials

์ด๋ ‡๊ฒŒ ๊ณต๋ถ€ํ•  ํŒจํ‚ค์ง€๋“ค์ด ์ •๋ง ๋งŽ์Šต๋‹ˆ๋‹ค. ์ด๋ฟ๋งŒ ์•„๋‹ˆ๋ผ, ํ”„๋กœ์ ํŠธ๋ฅผ ํ•ด๋ณผ ์ˆ˜๋„ ์žˆ๊ฒ ์ง€์š”

  • Robotis
Wiki
Founded in 1999, our company name ROBOTIS ( ROBOTIS = " ROBOT IS...") derived from a simple response to the philosophical question "What is a robot?" and since then we have been commercializing personal robots.
http://wiki.ros.org/robotis
  • Spot Micro ROS
mike4192/spotMicro
Video of robot: https://www.youtube.com/watch?v=S-uzWG9Z-5E This project is the source code for a Spot Micro quadruped, a 4 legged open source robot. This code implements motion control of a 3d printed spot micro robot, including sit, stand, angle and walk control. Supporting libraries provide additional capabilities, such as mapping through SLAM and a body mounted lidar.
https://github.com/mike4192/spotMicro
  • PixHawk
Robotics using ROS | PX4 User Guide
(Robot Operating System) is a general purpose robotics library that can be used with PX4 for offboard control. It uses the MAVROS node to communicate with PX4 running on hardware or using the Gazebo Simulator. This section contains topics about using ROS for offboard control with PX4.
https://docs.px4.io/master/en/ros/

...

๐ŸŽ‡์ง€๊ธˆ๊นŒ์ง€ ROS ๊ฐ•์˜๋ฅผ ์ˆ˜๊ฐ•ํ•ด์ฃผ์…”์„œ ์ •๋ง ๊ฐ์‚ฌํ•ฉ๋‹ˆ๋‹ค ๐ŸŽ†
๋”๋ถˆ์–ด, ์ดฌ์˜์— ๋„์›€์„ ์ฃผ์‹  G Camp, AI Robotics KR ๋ถ„๋“ค๊ป˜๋„ ๊ฐ์‚ฌ๋“œ๋ฆฝ๋‹ˆ๋‹ค ๐Ÿ˜‰