chest_camera_tracking.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # coding: utf-8
3 
4 # Copyright 2019 RT Corporation
5 #
6 # Licensed under the Apache License, Version 2.0 (the "License");
7 # you may not use this file except in compliance with the License.
8 # You may obtain a copy of the License at
9 #
10 # http://www.apache.org/licenses/LICENSE-2.0
11 #
12 # Unless required by applicable law or agreed to in writing, software
13 # distributed under the License is distributed on an "AS IS" BASIS,
14 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 # See the License for the specific language governing permissions and
16 # limitations under the License.
17 
18 import rospy
19 import math
20 import sys
21 
22 # for ObjectTracker
23 import cv2
24 import numpy as np
25 from sensor_msgs.msg import Image
26 from cv_bridge import CvBridge, CvBridgeError
27 from geometry_msgs.msg import Point
28 
29 # for WaistYaw
30 import actionlib
31 from control_msgs.msg import (
32  FollowJointTrajectoryAction,
33  FollowJointTrajectoryGoal,
34  JointTrajectoryControllerState
35 )
36 from trajectory_msgs.msg import JointTrajectoryPoint
37 
39  def __init__(self):
40  self._bridge = CvBridge()
41  self._image_sub = rospy.Subscriber("/sciurus17/chest_camera_node/image", Image, self._image_callback, queue_size=1)
42  self._image_pub = rospy.Publisher("~output_image", Image, queue_size=1)
43  self._object_rect = [0,0,0,0]
44  self._image_shape = Point()
45  self._object_detected = False
46 
47  self._CV_MAJOR_VERSION, _, _ = cv2.__version__.split('.')
48 
49 
50  def _image_callback(self, ros_image):
51  try:
52  input_image = self._bridge.imgmsg_to_cv2(ros_image, "bgr8")
53  except CvBridgeError as e:
54  rospy.logerr(e)
55 
56  # 画像のwidth, heightを取得
57  # Obtains the width and height of the image
58  self._image_shape.x = input_image.shape[1]
59  self._image_shape.y = input_image.shape[0]
60 
61  # 特定色のオブジェクトを検出
62  # Detects an object with a certain color
63  output_image = self._detect_orange_object(input_image)
64  # output_image = self._detect_blue_object(input_image)
65 
66  self._image_pub.publish(self._bridge.cv2_to_imgmsg(output_image, "bgr8"))
67 
68 
70  # 画像中心を0, 0とした座標系におけるオブジェクトの座標を出力
71  # オブジェクトの座標は-1.0 ~ 1.0に正規化される
72  # Returns the object coordinates where the image center is 0, 0
73  # The coordinate is normalized into -1.0 to 1.0
74 
75  object_center = Point(
76  self._object_rect[0] + self._object_rect[2] * 0.5,
77  self._object_rect[1] + self._object_rect[3] * 0.5,
78  0)
79 
80  # 画像の中心を0, 0とした座標系に変換
81  # Converts the coordinate where the image center is 0, 0
82  translated_point = Point()
83  translated_point.x = object_center.x - self._image_shape.x * 0.5
84  translated_point.y = -(object_center.y - self._image_shape.y * 0.5)
85 
86  # 正規化
87  # Normalize
88  normalized_point = Point()
89  if self._image_shape.x != 0 and self._image_shape.y != 0:
90  normalized_point.x = translated_point.x / (self._image_shape.x * 0.5)
91  normalized_point.y = translated_point.y / (self._image_shape.y * 0.5)
92 
93  return normalized_point
94 
95 
96  def object_detected(self):
97  return self._object_detected
98 
99 
100  def _detect_color_object(self, bgr_image, lower_color, upper_color):
101  # 画像から指定された色の物体を検出する
102  # Detects the specified colored object from the image
103 
104  MIN_OBJECT_SIZE = 7000 # px * px
105 
106  # BGR画像をHSV色空間に変換
107  # Converts the BGR image to HSV model
108  hsv = cv2.cvtColor(bgr_image, cv2.COLOR_BGR2HSV)
109 
110  # 色を抽出するマスクを生成
111  # Creates a mask to extract the color
112  mask = cv2.inRange(hsv, lower_color, upper_color)
113 
114  # マスクから輪郭を抽出
115  # Extracts the contours with the mask
116  if self._CV_MAJOR_VERSION == '4':
117  contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
118  else:
119  _, contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
120 
121  # 輪郭を長方形に変換し、配列に格納
122  # Converts the contour to a rectangle and store it in a vector
123  rects = []
124  for contour in contours:
125  approx = cv2.convexHull(contour)
126  rect = cv2.boundingRect(approx)
127  rects.append(rect)
128 
129  self._object_detected = False
130  if len(rects) > 0:
131  # 最も大きい長方形を抽出
132  # Extracts the largest rectangle
133  rect = max(rects, key=(lambda x: x[2] * x[3]))
134 
135  # 長方形が小さければ検出判定にしない
136  # Updates the detection result to false if the rectangle is small
137  if rect[2] * rect[3] > MIN_OBJECT_SIZE:
138  # 抽出した長方形を画像に描画する
139  # Draw the rectangle on the image
140  cv2.rectangle(bgr_image,
141  (rect[0], rect[1]),
142  (rect[0] + rect[2], rect[1] + rect[3]),
143  (0, 0, 255), thickness=2)
144 
145  self._object_rect = rect
146  self._object_detected = True
147 
148  return bgr_image
149 
150 
151  def _detect_orange_object(self, bgr_image):
152  # H: 0 ~ 179 (0 ~ 360°)
153  # S: 0 ~ 255 (0 ~ 100%)
154  # V: 0 ~ 255 (0 ~ 100%)
155  lower_orange = np.array([5,127,127])
156  upper_orange = np.array([20,255,255])
157 
158  return self._detect_color_object(bgr_image, lower_orange, upper_orange)
159 
160 
161  def _detect_blue_object(self, bgr_image):
162  # H: 0 ~ 179 (0 ~ 360°)
163  # S: 0 ~ 255 (0 ~ 100%)
164  # V: 0 ~ 255 (0 ~ 100%)
165  lower_blue = np.array([100,127,127])
166  upper_blue = np.array([110,255,255])
167 
168  return self._detect_color_object(bgr_image, lower_blue, upper_blue)
169 
170 
171 class WaistYaw(object):
172  def __init__(self):
173  self.__client = actionlib.SimpleActionClient("/sciurus17/controller3/waist_yaw_controller/follow_joint_trajectory",
174  FollowJointTrajectoryAction)
175  self.__client.wait_for_server(rospy.Duration(5.0))
176  if not self.__client.wait_for_server(rospy.Duration(5.0)):
177  rospy.logerr("Action Server Not Found")
178  rospy.signal_shutdown("Action Server not found")
179  sys.exit(1)
180 
181  self._state_sub = rospy.Subscriber("/sciurus17/controller3/waist_yaw_controller/state",
182  JointTrajectoryControllerState, self._state_callback, queue_size=1)
183 
184  self._state_received = False
185  self._current_yaw = 0.0 # Degree
186 
187  def _state_callback(self, state):
188  # 腰の現在角度を取得
189  # Returns the current angle of the waist
190 
191  self._state_received = True
192  yaw_radian = state.actual.positions[0]
193  self._current_yaw = math.degrees(yaw_radian)
194 
195 
196  def state_received(self):
197  return self._state_received
198 
199 
200  def get_current_yaw(self):
201  return self._current_yaw
202 
203 
204  def set_angle(self, yaw_angle, goal_secs=1.0e-9):
205  # 腰を指定角度に動かす
206  # Moves the waist to the specified angle
207  goal = FollowJointTrajectoryGoal()
208  goal.trajectory.joint_names = ["waist_yaw_joint"]
209 
210  yawpoint = JointTrajectoryPoint()
211  yawpoint.positions.append(yaw_angle)
212  yawpoint.time_from_start = rospy.Duration(goal_secs)
213  goal.trajectory.points.append(yawpoint)
214 
215  self.__client.send_goal(goal)
216  self.__client.wait_for_result(rospy.Duration(0.1))
217  return self.__client.get_result()
218 
219 
221  # shutdown時に0度へ戻る
222  # Sets the waist angle to 0 deg when shutting down
223  waist_yaw.set_angle(math.radians(0), 3.0)
224 
225 
226 def main():
227  r = rospy.Rate(60)
228 
229  rospy.on_shutdown(hook_shutdown)
230 
231  # オブジェクト追跡のしきい値
232  # 正規化された座標系(px, px)
233  # The threshold of the object tracking
234  # Normalized coordinates is (px, px)
235  THRESH_X = 0.05
236 
237  # 腰の初期角度 Degree
238  # The inital angle of the waist in degrees
239  INITIAL_YAW_ANGLE = 0
240 
241  # 腰の制御角度リミット値 Degree
242  # The waist angle limit (max/min) in degrees
243  MAX_YAW_ANGLE = 120
244  MIN_YAW_ANGLE = -120
245 
246  # 腰の制御量
247  # 値が大きいほど腰を大きく動かす
248  # The control amount of the waist
249  # The waist moves more if the gain is bigger
250  OPERATION_GAIN_X = 5.0
251 
252  # 初期角度に戻る時の制御角度 Degree
253  # The degree when returning to the initial pose
254  RESET_OPERATION_ANGLE = 1
255 
256  # 現在の腰角度を取得する
257  # ここで現在の腰角度を取得することで、ゆっくり初期角度へ戻る
258  # Recieves the current waist angle
259  # By recieving the waist angle here, it moves to the initial pose slowly
260  while not waist_yaw.state_received():
261  pass
262  yaw_angle = waist_yaw.get_current_yaw()
263 
264  look_object = False
265  detection_timestamp = rospy.Time.now()
266 
267  while not rospy.is_shutdown():
268  # 正規化されたオブジェクトの座標を取得
269  # Recieves the normalized object coordinates
270  object_position = object_tracker.get_object_position()
271 
272  if object_tracker.object_detected():
273  detection_timestamp = rospy.Time.now()
274  look_object = True
275  else:
276  lost_time = rospy.Time.now() - detection_timestamp
277  # 一定時間オブジェクトが見つからない場合は初期角度に戻る
278  # If it doesn't detect any object for a certain amount of time,
279  # it will return to the initial angle
280  if lost_time.to_sec() > 1.0:
281  look_object = False
282 
283  if look_object:
284  # オブジェクトが画像中心にくるように首を動かす
285  # Moves the neck so that the object comes to the middle of the image
286  if math.fabs(object_position.x) > THRESH_X:
287  yaw_angle += -object_position.x * OPERATION_GAIN_X
288 
289  # 腰の角度を制限する
290  # Limits the waist angles
291  if yaw_angle > MAX_YAW_ANGLE:
292  yaw_angle = MAX_YAW_ANGLE
293  if yaw_angle < MIN_YAW_ANGLE:
294  yaw_angle = MIN_YAW_ANGLE
295 
296  else:
297  # ゆっくり初期角度へ戻る
298  # Returns to the initial angle slowly
299  diff_yaw_angle = yaw_angle - INITIAL_YAW_ANGLE
300  if math.fabs(diff_yaw_angle) > RESET_OPERATION_ANGLE:
301  yaw_angle -= math.copysign(RESET_OPERATION_ANGLE, diff_yaw_angle)
302  else:
303  yaw_angle = 0
304 
305  waist_yaw.set_angle(math.radians(yaw_angle))
306 
307  r.sleep()
308 
309 
310 if __name__ == '__main__':
311  rospy.init_node("chest_camera_tracking")
312 
313  waist_yaw = WaistYaw()
314  object_tracker = ObjectTracker()
315 
316  main()
317 
chest_camera_tracking.hook_shutdown
def hook_shutdown()
Definition: chest_camera_tracking.py:220
chest_camera_tracking.ObjectTracker.get_object_position
def get_object_position(self)
Definition: chest_camera_tracking.py:69
chest_camera_tracking.WaistYaw._state_received
_state_received
Definition: chest_camera_tracking.py:184
chest_camera_tracking.ObjectTracker._object_rect
_object_rect
Definition: chest_camera_tracking.py:43
chest_camera_tracking.ObjectTracker._image_pub
_image_pub
Definition: chest_camera_tracking.py:42
chest_camera_tracking.WaistYaw.get_current_yaw
def get_current_yaw(self)
Definition: chest_camera_tracking.py:200
chest_camera_tracking.ObjectTracker.__init__
def __init__(self)
Definition: chest_camera_tracking.py:39
chest_camera_tracking.ObjectTracker._detect_color_object
def _detect_color_object(self, bgr_image, lower_color, upper_color)
Definition: chest_camera_tracking.py:100
actionlib::SimpleActionClient
chest_camera_tracking.ObjectTracker.object_detected
def object_detected(self)
Definition: chest_camera_tracking.py:96
chest_camera_tracking.ObjectTracker._bridge
_bridge
Definition: chest_camera_tracking.py:40
chest_camera_tracking.ObjectTracker._image_sub
_image_sub
Definition: chest_camera_tracking.py:41
chest_camera_tracking.ObjectTracker._image_shape
_image_shape
Definition: chest_camera_tracking.py:44
chest_camera_tracking.WaistYaw.__init__
def __init__(self)
Definition: chest_camera_tracking.py:172
chest_camera_tracking.ObjectTracker._image_callback
def _image_callback(self, ros_image)
Definition: chest_camera_tracking.py:50
chest_camera_tracking.ObjectTracker._detect_orange_object
def _detect_orange_object(self, bgr_image)
Definition: chest_camera_tracking.py:151
chest_camera_tracking.ObjectTracker._object_detected
_object_detected
Definition: chest_camera_tracking.py:45
chest_camera_tracking.ObjectTracker._CV_MAJOR_VERSION
_CV_MAJOR_VERSION
Definition: chest_camera_tracking.py:116
chest_camera_tracking.main
def main()
Definition: chest_camera_tracking.py:226
chest_camera_tracking.WaistYaw.__client
__client
Definition: chest_camera_tracking.py:173
chest_camera_tracking.WaistYaw._state_sub
_state_sub
Definition: chest_camera_tracking.py:181
chest_camera_tracking.WaistYaw._state_callback
def _state_callback(self, state)
Definition: chest_camera_tracking.py:187
chest_camera_tracking.WaistYaw
Definition: chest_camera_tracking.py:171
chest_camera_tracking.WaistYaw._current_yaw
_current_yaw
Definition: chest_camera_tracking.py:185
chest_camera_tracking.ObjectTracker._detect_blue_object
def _detect_blue_object(self, bgr_image)
Definition: chest_camera_tracking.py:161
chest_camera_tracking.ObjectTracker
Definition: chest_camera_tracking.py:38
chest_camera_tracking.WaistYaw.set_angle
def set_angle(self, yaw_angle, goal_secs=1.0e-9)
Definition: chest_camera_tracking.py:204
chest_camera_tracking.WaistYaw.state_received
def state_received(self)
Definition: chest_camera_tracking.py:196


sciurus17_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Fri Aug 2 2024 08:37:20