|
| 1 | +# Copyright 2020 RT Corporation |
| 2 | +# |
| 3 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +# you may not use this file except in compliance with the License. |
| 5 | +# You may obtain a copy of the License at |
| 6 | +# |
| 7 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +# |
| 9 | +# Unless required by applicable law or agreed to in writing, software |
| 10 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +# See the License for the specific language governing permissions and |
| 13 | +# limitations under the License. |
| 14 | + |
| 15 | + |
| 16 | +import rclpy |
| 17 | +from rclpy.node import Node |
| 18 | + |
| 19 | +import numpy as np |
| 20 | + |
| 21 | +# from std_msgs.msg import String |
| 22 | +from geometry_msgs.msg import TransformStamped |
| 23 | +from sensor_msgs.msg import CameraInfo, Image |
| 24 | +import cv2 |
| 25 | +from cv2 import aruco |
| 26 | +from cv_bridge import CvBridge |
| 27 | +import tf2_ros |
| 28 | + |
| 29 | +from crane_x7_examples_py.utils import rotation_matrix_to_quaternion |
| 30 | + |
| 31 | + |
| 32 | +class ImageSubscriber(Node): |
| 33 | + def __init__(self): |
| 34 | + super().__init__("aruco_detection") |
| 35 | + self.image_subscription = self.create_subscription( |
| 36 | + Image, "/camera/color/image_raw", self.listener_callback, 10 |
| 37 | + ) |
| 38 | + self.camera_info_subscription = self.create_subscription( |
| 39 | + CameraInfo, "/camera/color/camera_info", self.listener_callback, 10 |
| 40 | + ) |
| 41 | + self.tf_broadcaster = tf2_ros.TransformBroadcaster() |
| 42 | + |
| 43 | + self.camera_info = None |
| 44 | + self.bridge = CvBridge() |
| 45 | + |
| 46 | + def image_callback(self, msg): |
| 47 | + # 画像データをROSのメッセージからOpenCVの配列に変換 |
| 48 | + cv_img = self.bridge.imgmsg_to_cv2(msg, desired_encoding=msg.encoding) |
| 49 | + cv_img = cv2.cvtColor(cv_img, cv2.COLOR_RGB2BGR) |
| 50 | + |
| 51 | + if self.camera_info: |
| 52 | + # ArUcoマーカのデータセットを読み込む |
| 53 | + # DICT_6x6_50は6x6ビットのマーカが50個収録されたもの |
| 54 | + MARKER_DICT = aruco.getPredefinedDictionary(aruco.DICT_6X6_50) |
| 55 | + |
| 56 | + # マーカーID |
| 57 | + ids = [] |
| 58 | + |
| 59 | + # 画像座標系上のマーカ頂点位置 |
| 60 | + corners = [] |
| 61 | + |
| 62 | + # マーカの検出 |
| 63 | + corners, ids, _ = aruco.detectMarkers(cv_img, MARKER_DICT) |
| 64 | + |
| 65 | + # マーカの検出数 |
| 66 | + n_markers = len(ids) |
| 67 | + |
| 68 | + # カメラパラメータ |
| 69 | + CAMERA_MATRIX = np.array(self.camera_info['k']).reshape(3, 3) |
| 70 | + DIST_COEFFS = np.array(self.camera_info['d']).reshape(1, 5) |
| 71 | + |
| 72 | + # マーカ一辺の長さ 0.04 [m] |
| 73 | + MARKER_LENGTH = 0.04 |
| 74 | + |
| 75 | + # マーカが一つ以上検出された場合、マーカの位置姿勢をtfで配信 |
| 76 | + if n_markers > 0: |
| 77 | + for i in range(n_markers): |
| 78 | + # 画像座標系上のマーカ位置を三次元のカメラ座標系に変換 |
| 79 | + rvecs, tvecs, _ = cv2.aruco.estimatePoseSingleMarkers( |
| 80 | + corners, MARKER_LENGTH, CAMERA_MATRIX, DIST_COEFFS) |
| 81 | + # tfの配信 |
| 82 | + t = TransformStamped() |
| 83 | + t.header.stamp = self.get_clock().now().to_msg() |
| 84 | + t.header.frame_id = "camera_color_optical_frame" |
| 85 | + t.child_frame_id = "target_" + str(ids[i][0]) |
| 86 | + t.transform.translation.x = tvecs[i][0][0] |
| 87 | + t.transform.translation.y = tvecs[i][0][1] |
| 88 | + t.transform.translation.z = tvecs[i][0][2] |
| 89 | + # 回転ベクトル→回転行列 |
| 90 | + rotation_matrix, _ = cv2.Rodrigues(rvecs[i]) |
| 91 | + # 回転行列からクォータニオンを求める |
| 92 | + q = rotation_matrix_to_quaternion(rotation_matrix) |
| 93 | + t.transform.rotation.x = q.x |
| 94 | + t.transform.rotation.y = q.y |
| 95 | + t.transform.rotation.z = q.z |
| 96 | + t.transform.rotation.w = q.w |
| 97 | + self.tf_broadcaster.sendTransform(t) |
| 98 | + |
| 99 | + def camera_info_callback(self, msg): |
| 100 | + self.camera_info = msg |
| 101 | + |
| 102 | + |
| 103 | +def main(args=None): |
| 104 | + rclpy.init(args=args) |
| 105 | + |
| 106 | + image_subscriber = ImageSubscriber() |
| 107 | + rclpy.spin(image_subscriber) |
| 108 | + |
| 109 | + # Destroy the node explicitly |
| 110 | + # (optional - otherwise it will be done automatically |
| 111 | + # when the garbage collector destroys the node object) |
| 112 | + image_subscriber.destroy_node() |
| 113 | + rclpy.shutdown() |
| 114 | + |
| 115 | + |
| 116 | +if __name__ == "__main__": |
| 117 | + main() |
0 commit comments