You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

aruco_detector_node.py 6.4KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146
  1. from numpy.lib.function_base import _angle_dispatcher
  2. import rclpy
  3. from rclpy.node import Node
  4. from rclpy.qos import qos_profile_sensor_data
  5. from cv_bridge import CvBridge
  6. import numpy as np
  7. import cv2
  8. from transforms3d.quaternions import mat2quat
  9. from transforms3d.euler import mat2euler
  10. from aruco_detector import yaml_handling
  11. from sensor_msgs.msg import CompressedImage, Image
  12. from geometry_msgs.msg import Pose
  13. from aruco_interfaces.msg import ArucoMarkerPose
  14. class ArucoDetectorNode(rclpy.node.Node):
  15. def __init__(self):
  16. super().__init__('aruco_detector_node')
  17. # Declare parameters
  18. self.declare_parameter("marker_size", .1)
  19. self.declare_parameter("aruco_dictionary_id", "DICT_6X6_100")
  20. self.declare_parameter("input_image_topic", "/image_raw/compressed")
  21. self.declare_parameter("url_yaml_file", "file:///home/ros2/dev2_ws/src/aruco_detector/hd_pro_webcam_c920.yaml") # url to yaml file (calibration file)
  22. # Read parameters
  23. self.marker_size = self.get_parameter("marker_size").get_parameter_value().double_value
  24. dictionary_id_name = self.get_parameter("aruco_dictionary_id").get_parameter_value().string_value
  25. input_image_topic = self.get_parameter("input_image_topic").get_parameter_value().string_value
  26. url_yaml_file = self.get_parameter("url_yaml_file").get_parameter_value().string_value
  27. # check dictionary_id_name
  28. try:
  29. dictionary_id = cv2.aruco.__getattribute__(dictionary_id_name)
  30. if type(dictionary_id) != type(cv2.aruco.DICT_5X5_100):
  31. raise AttributeError
  32. except AttributeError:
  33. self.get_logger().error("bad aruco_dictionary_id: {}".format(dictionary_id_name))
  34. options = "\n".join([s for s in dir(cv2.aruco) if s.startswith("DICT")])
  35. self.get_logger().error("valid options: {}".format(options))
  36. # Set up subscriber
  37. self.create_subscription(CompressedImage, input_image_topic, self.image_callback, qos_profile_sensor_data) # subsribes the images from the camera
  38. # Set up publishers
  39. self.publisher_marker_poses = self.create_publisher(ArucoMarkerPose, '/aruco/aruco_poses', 10) # publishes the current poses
  40. self.publisher_output_images = self.create_publisher(CompressedImage, '/aruco/aruco_output_images/compressed', 10) # publishes the images with the detected aruco-tags
  41. # Load the camera parameters from yaml-file
  42. camera_info_msg = yaml_handling.yaml_to_CameraInfo("/home/ros2/dev2_ws/src/aruco_detector/hd_pro_webcam_c920.yaml")#url_yaml_file)
  43. if camera_info_msg is None:
  44. self.get_logger().warn("No camera info has been received!")
  45. return
  46. self.intrinsic_mat = np.reshape(np.array(camera_info_msg.k), (3, 3))
  47. self.distortion = np.array(camera_info_msg.d)
  48. self.aruco_dictionary = cv2.aruco.Dictionary_get(dictionary_id)
  49. self.aruco_parameters = cv2.aruco.DetectorParameters_create()
  50. self.bridge = CvBridge()
  51. def image_callback(self, img_msg):
  52. cv_image = self.bridge.compressed_imgmsg_to_cv2(img_msg,desired_encoding='passthrough')
  53. corners, marker_ids, rejected = cv2.aruco.detectMarkers(cv_image,
  54. self.aruco_dictionary,
  55. parameters=self.aruco_parameters)
  56. #check if marker is detected, then estimate pose an publish
  57. if marker_ids is not None:
  58. rvecs, tvecs, _objPoints = cv2.aruco.estimatePoseSingleMarkers(corners,
  59. self.marker_size,
  60. self.intrinsic_mat,
  61. self.distortion)
  62. #self.get_logger().error("rvecs: {}".format(rvecs))
  63. pose_array = ArucoMarkerPose()
  64. for i, marker_id in enumerate(marker_ids):
  65. pose = Pose()
  66. pose.position.x = tvecs[i][0][0]
  67. pose.position.y = tvecs[i][0][1]
  68. pose.position.z = tvecs[i][0][2]
  69. rot_matrix = np.eye(4)
  70. rot_matrix[0:3, 0:3] = cv2.Rodrigues(np.array(rvecs[i][0]))[0]
  71. import math
  72. angle = math.acos(rot_matrix[0][0])*(180/math.pi)
  73. angle_psi, angle_theta, angle_phi = mat2euler(rot_matrix)
  74. #quat = mat2quat(rot_matrix[0:3, 0:3])
  75. self.get_logger().error("angle_theta: \n{}\n\n".format(angle_theta*(180/math.pi)))
  76. self.get_logger().error("angle_phi: \n{}\n\n".format(angle_phi*(180/math.pi)))
  77. self.get_logger().error("angle_psi: \n{}\n\n".format(angle_psi*(180/math.pi)))
  78. # parameter einfügen für unterscheidung zwischen 2D und 3D
  79. # einfache if abfrage
  80. pose.orientation.x = 0.0 #quat[0]
  81. pose.orientation.y = 0.0 #quat[1]
  82. pose.orientation.z = math.sin((angle_phi) / 2) #quat[2]
  83. pose.orientation.w = math.cos((angle_phi) / 2) #quat[3]
  84. pose_array.poses.append(pose)
  85. pose_array.marker_ids.append(marker_id[0])
  86. self.publisher_marker_poses.publish(pose_array)
  87. output_img = cv2.aruco.drawAxis(cv_image,
  88. self.intrinsic_mat,
  89. self.distortion,
  90. rvecs,
  91. tvecs,
  92. 0.5
  93. )
  94. output_img = cv2.aruco.drawDetectedMarkers(cv_image, corners, marker_ids)
  95. output_img_compressed = self.bridge.cv2_to_compressed_imgmsg(output_img, dst_format='jpg')
  96. self.publisher_output_images.publish(output_img_compressed)
  97. def main(args=None):
  98. rclpy.init(args=args)
  99. minimal_publisher = ArucoDetectorNode()
  100. rclpy.spin(minimal_publisher)
  101. minimal_publisher.destroy_node()
  102. rclpy.shutdown()
  103. if __name__ == '__main__':
  104. main()