25 from sensor_msgs.msg
import Image
26 from cv_bridge
import CvBridge, CvBridgeError
27 from geometry_msgs.msg
import Point
31 from control_msgs.msg
import (
32 FollowJointTrajectoryAction,
33 FollowJointTrajectoryGoal,
34 JointTrajectoryControllerState
36 from trajectory_msgs.msg
import JointTrajectoryPoint
42 self.
_image_pub = rospy.Publisher(
"~output_image", Image, queue_size=1)
52 input_image = self.
_bridge.imgmsg_to_cv2(ros_image,
"bgr8")
53 except CvBridgeError
as e:
75 object_center = Point(
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)
88 normalized_point = Point()
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)
93 return normalized_point
104 MIN_OBJECT_SIZE = 7000
108 hsv = cv2.cvtColor(bgr_image, cv2.COLOR_BGR2HSV)
112 mask = cv2.inRange(hsv, lower_color, upper_color)
117 contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
119 _, contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
124 for contour
in contours:
125 approx = cv2.convexHull(contour)
126 rect = cv2.boundingRect(approx)
133 rect = max(rects, key=(
lambda x: x[2] * x[3]))
137 if rect[2] * rect[3] > MIN_OBJECT_SIZE:
140 cv2.rectangle(bgr_image,
142 (rect[0] + rect[2], rect[1] + rect[3]),
143 (0, 0, 255), thickness=2)
155 lower_orange = np.array([5,127,127])
156 upper_orange = np.array([20,255,255])
165 lower_blue = np.array([100,127,127])
166 upper_blue = np.array([110,255,255])
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")
181 self.
_state_sub = rospy.Subscriber(
"/sciurus17/controller3/waist_yaw_controller/state",
192 yaw_radian = state.actual.positions[0]
207 goal = FollowJointTrajectoryGoal()
208 goal.trajectory.joint_names = [
"waist_yaw_joint"]
210 yawpoint = JointTrajectoryPoint()
211 yawpoint.positions.append(yaw_angle)
212 yawpoint.time_from_start = rospy.Duration(goal_secs)
213 goal.trajectory.points.append(yawpoint)
216 self.
__client.wait_for_result(rospy.Duration(0.1))
223 waist_yaw.set_angle(math.radians(0), 3.0)
229 rospy.on_shutdown(hook_shutdown)
239 INITIAL_YAW_ANGLE = 0
250 OPERATION_GAIN_X = 5.0
254 RESET_OPERATION_ANGLE = 1
260 while not waist_yaw.state_received():
262 yaw_angle = waist_yaw.get_current_yaw()
265 detection_timestamp = rospy.Time.now()
267 while not rospy.is_shutdown():
270 object_position = object_tracker.get_object_position()
272 if object_tracker.object_detected():
273 detection_timestamp = rospy.Time.now()
276 lost_time = rospy.Time.now() - detection_timestamp
280 if lost_time.to_sec() > 1.0:
286 if math.fabs(object_position.x) > THRESH_X:
287 yaw_angle += -object_position.x * OPERATION_GAIN_X
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
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)
305 waist_yaw.set_angle(math.radians(yaw_angle))
310 if __name__ ==
'__main__':
311 rospy.init_node(
"chest_camera_tracking")