25 from std_msgs.msg
import Int32
26 from sensor_msgs.msg
import Image
27 from cv_bridge
import CvBridge, CvBridgeError
28 from geometry_msgs.msg
import Point
32 from control_msgs.msg
import (
33 FollowJointTrajectoryAction,
34 FollowJointTrajectoryGoal,
35 JointTrajectoryControllerState
37 from trajectory_msgs.msg
import JointTrajectoryPoint
52 self.
_image_pub = rospy.Publisher(
"~output_image", Image, queue_size=1)
67 input_image = self.
_bridge.imgmsg_to_cv2(ros_image,
"bgr8")
68 except CvBridgeError
as e:
77 input_image = self.
_bridge.imgmsg_to_cv2(ros_image,
"passthrough")
78 except CvBridgeError
as e:
88 if output_image
is not False:
100 object_center = Point(
107 translated_point = Point()
108 translated_point.x = object_center.x - self.
_image_shape.x * 0.5
109 translated_point.y = -(object_center.y - self.
_image_shape.y * 0.5)
113 normalized_point = Point()
115 normalized_point.x = translated_point.x / (self.
_image_shape.x * 0.5)
116 normalized_point.y = translated_point.y / (self.
_image_shape.y * 0.5)
118 return normalized_point
128 MIN_OBJECT_SIZE = 10000
129 MAX_OBJECT_SIZE = 80000
152 if output_image
is None:
157 for i, depth
in enumerate(DETECTION_DEPTH):
160 mask = cv2.inRange(input_depth_image, depth[0], depth[1])
165 contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
167 _, contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
171 for contour
in contours:
172 approx = cv2.convexHull(contour)
173 rect = cv2.boundingRect(approx)
179 rect = max(rects, key=(
lambda x: x[2] * x[3]))
181 rect_size = rect[2] * rect[3]
185 if rect_size > MIN_OBJECT_SIZE
and rect_size < MAX_OBJECT_SIZE:
188 cv2.rectangle(output_image,
190 (rect[0] + rect[2], rect[1] + rect[3]),
191 RECT_COLOR[i], thickness=2)
198 object_depth = input_depth_image[
199 rect[1]:rect[1]+rect[3],
200 rect[0]:rect[0]+rect[2]]
208 (rect[0], rect[1]+30),
209 cv2.FONT_HERSHEY_SIMPLEX,
219 FollowJointTrajectoryAction)
220 self.
__client.wait_for_server(rospy.Duration(5.0))
221 if not self.
__client.wait_for_server(rospy.Duration(5.0)):
222 rospy.logerr(
"Action Server Not Found")
223 rospy.signal_shutdown(
"Action Server not found")
226 self.
_state_sub = rospy.Subscriber(
"/sciurus17/controller3/neck_controller/state",
239 yaw_radian = state.actual.positions[0]
240 pitch_radian = state.actual.positions[1]
258 def set_angle(self, yaw_angle, pitch_angle, goal_secs=1.0e-9):
261 goal = FollowJointTrajectoryGoal()
262 goal.trajectory.joint_names = [
"neck_yaw_joint",
"neck_pitch_joint"]
264 yawpoint = JointTrajectoryPoint()
265 yawpoint.positions.append(yaw_angle)
266 yawpoint.positions.append(pitch_angle)
267 yawpoint.time_from_start = rospy.Duration(goal_secs)
268 goal.trajectory.points.append(yawpoint)
271 self.
__client.wait_for_result(rospy.Duration(0.1))
278 neck.set_angle(math.radians(0), math.radians(0), 3.0)
284 rospy.on_shutdown(hook_shutdown)
295 INITIAL_YAW_ANGLE = 0
296 INITIAL_PITCH_ANGLE = 0
303 MIN_PITCH_ANGLE = -70
309 OPERATION_GAIN_X = 5.0
310 OPERATION_GAIN_Y = 5.0
314 RESET_OPERATION_ANGLE = 3
320 while not neck.state_received():
322 yaw_angle = neck.get_current_yaw()
323 pitch_angle = neck.get_current_pitch()
326 detection_timestamp = rospy.Time.now()
328 while not rospy.is_shutdown():
331 object_position = object_tracker.get_object_position()
333 if object_tracker.object_detected():
334 detection_timestamp = rospy.Time.now()
337 lost_time = rospy.Time.now() - detection_timestamp
341 if lost_time.to_sec() > 1.0:
347 if math.fabs(object_position.x) > THRESH_X:
348 yaw_angle += -object_position.x * OPERATION_GAIN_X
350 if math.fabs(object_position.y) > THRESH_Y:
351 pitch_angle += object_position.y * OPERATION_GAIN_Y
355 if yaw_angle > MAX_YAW_ANGLE:
356 yaw_angle = MAX_YAW_ANGLE
357 if yaw_angle < MIN_YAW_ANGLE:
358 yaw_angle = MIN_YAW_ANGLE
360 if pitch_angle > MAX_PITCH_ANGLE:
361 pitch_angle = MAX_PITCH_ANGLE
362 if pitch_angle < MIN_PITCH_ANGLE:
363 pitch_angle = MIN_PITCH_ANGLE
368 diff_yaw_angle = yaw_angle - INITIAL_YAW_ANGLE
369 if math.fabs(diff_yaw_angle) > RESET_OPERATION_ANGLE:
370 yaw_angle -= math.copysign(RESET_OPERATION_ANGLE, diff_yaw_angle)
372 yaw_angle = INITIAL_YAW_ANGLE
374 diff_pitch_angle = pitch_angle - INITIAL_PITCH_ANGLE
375 if math.fabs(diff_pitch_angle) > RESET_OPERATION_ANGLE:
376 pitch_angle -= math.copysign(RESET_OPERATION_ANGLE, diff_pitch_angle)
378 pitch_angle = INITIAL_PITCH_ANGLE
380 neck.set_angle(math.radians(yaw_angle), math.radians(pitch_angle))
385 if __name__ ==
'__main__':
386 rospy.init_node(
"depth_camera_tracking")