11 from sensor_msgs.msg
import Image
12 from cv_bridge
import CvBridge, CvBridgeError
13 from geometry_msgs.msg
import Point
17 from control_msgs.msg
import (
18 FollowJointTrajectoryAction,
19 FollowJointTrajectoryGoal,
20 JointTrajectoryControllerState
22 from trajectory_msgs.msg
import JointTrajectoryPoint
28 self.
_image_pub = rospy.Publisher(
"~output_image", Image, queue_size=1)
38 input_image = self.
_bridge.imgmsg_to_cv2(ros_image,
"bgr8")
39 except CvBridgeError
as e:
57 object_center = Point(
63 translated_point = Point()
64 translated_point.x = object_center.x - self.
_image_shape.x * 0.5
65 translated_point.y = -(object_center.y - self.
_image_shape.y * 0.5)
68 normalized_point = Point()
70 normalized_point.x = translated_point.x / (self.
_image_shape.x * 0.5)
71 normalized_point.y = translated_point.y / (self.
_image_shape.y * 0.5)
73 return normalized_point
83 MIN_OBJECT_SIZE = 7000
86 hsv = cv2.cvtColor(bgr_image, cv2.COLOR_BGR2HSV)
89 mask = cv2.inRange(hsv, lower_color, upper_color)
93 contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
95 _, contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
99 for contour
in contours:
100 approx = cv2.convexHull(contour)
101 rect = cv2.boundingRect(approx)
107 rect = max(rects, key=(
lambda x: x[2] * x[3]))
110 if rect[2] * rect[3] > MIN_OBJECT_SIZE:
112 cv2.rectangle(bgr_image,
114 (rect[0] + rect[2], rect[1] + rect[3]),
115 (0, 0, 255), thickness=2)
127 lower_orange = np.array([5,127,127])
128 upper_orange = np.array([20,255,255])
137 lower_blue = np.array([100,127,127])
138 upper_blue = np.array([110,255,255])
146 FollowJointTrajectoryAction)
147 self.
__client.wait_for_server(rospy.Duration(5.0))
148 if not self.
__client.wait_for_server(rospy.Duration(5.0)):
149 rospy.logerr(
"Action Server Not Found")
150 rospy.signal_shutdown(
"Action Server not found")
153 self.
_state_sub = rospy.Subscriber(
"/sciurus17/controller3/waist_yaw_controller/state",
163 yaw_radian = state.actual.positions[0]
177 goal = FollowJointTrajectoryGoal()
178 goal.trajectory.joint_names = [
"waist_yaw_joint"]
180 yawpoint = JointTrajectoryPoint()
181 yawpoint.positions.append(yaw_angle)
182 yawpoint.time_from_start = rospy.Duration(goal_secs)
183 goal.trajectory.points.append(yawpoint)
186 self.
__client.wait_for_result(rospy.Duration(0.1))
192 waist_yaw.set_angle(math.radians(0), 3.0)
198 rospy.on_shutdown(hook_shutdown)
205 INITIAL_YAW_ANGLE = 0
213 OPERATION_GAIN_X = 5.0
216 RESET_OPERATION_ANGLE = 1
220 while not waist_yaw.state_received():
222 yaw_angle = waist_yaw.get_current_yaw()
225 detection_timestamp = rospy.Time.now()
227 while not rospy.is_shutdown():
229 object_position = object_tracker.get_object_position()
231 if object_tracker.object_detected():
232 detection_timestamp = rospy.Time.now()
235 lost_time = rospy.Time.now() - detection_timestamp
237 if lost_time.to_sec() > 1.0:
242 if math.fabs(object_position.x) > THRESH_X:
243 yaw_angle += -object_position.x * OPERATION_GAIN_X
246 if yaw_angle > MAX_YAW_ANGLE:
247 yaw_angle = MAX_YAW_ANGLE
248 if yaw_angle < MIN_YAW_ANGLE:
249 yaw_angle = MIN_YAW_ANGLE
253 diff_yaw_angle = yaw_angle - INITIAL_YAW_ANGLE
254 if math.fabs(diff_yaw_angle) > RESET_OPERATION_ANGLE:
255 yaw_angle -= math.copysign(RESET_OPERATION_ANGLE, diff_yaw_angle)
259 waist_yaw.set_angle(math.radians(yaw_angle))
264 if __name__ ==
'__main__':
265 rospy.init_node(
"chest_camera_tracking")
def get_object_position(self)
def set_angle(self, yaw_angle, goal_secs=1.0e-9)
def _detect_blue_object(self, bgr_image)
def _detect_color_object(self, bgr_image, lower_color, upper_color)
def get_current_yaw(self)
def object_detected(self)
def _detect_orange_object(self, bgr_image)
def _image_callback(self, ros_image)
def _state_callback(self, state)