vision_pipeline module¶
-
class
vision_pipeline.
VisionPipeline
(depth_res=(720, 1280), rgb_res=(720, 1280), align_to='rgb', marker_size=3.75, marker_type=0, required_marker_id=1, debug=0, padding=50, config_file='./vision/config.yaml', fps_moving_window_size=10)¶ Bases:
object
This is a class for initializing Intel Pyrealsense2 D435i camera and also finding depth and rgb frames along with detection of aruco marker.
- Attributes:
- depth_res: defines the depth resolution. Default is (720, 1080).
rgb_res: defines the rgb resolution. Default is (720, 1080).
align_to: defines frame to which alignment must be done. Default is “rgb”.
marker_size: defines the marker size of the aruco tag. Default is 3.75.
marker_type: defines the aruco marker type. Default is DICT_4X4_50.
marker_dict: gets the required aruco dictionary.
require_marker_id: defines the marker id of the aruco tag placed on the drone.
calib_file_path: defines the path for camera calibration.
DEBUG: a flag to enable prints in code for debugging. Default is False.
-
calibrate_yaw
()¶ Updates the estimated initial yaw in the rotation vector, by taking median of multiple yaw readings.
- Parameters:
- None
- Returns:
- None
-
cam_init
()¶ Initializes camera and starts ArUco detection.
- Parameters:
- None
- Returns:
- None
-
cam_process
(cam_queue)¶ Processes video frames to detect and locate Aruco markers, find depth value using the depth frame and then updating the camera data queue with the estimated readings.
- Parameters:
- cam_queue: a queue that is storing camera data where the latest reading is accessed by its last element
- Returns:
- None
-
depth_from_marker
(depth_frame, marker_corners, kernel_size=1)¶ Finds depth from the estimated pose obtained from the ArUco tag. Parameters:
depth_frame: depth image from realsense
marker_corners: contains the list of aruco marker corners
kernel_size: contains the size of the kernel- Returns:
- depths: depth of the point filtered using median filter
-
detect_marker
(frame)¶ Detection of ArUco markers returning its corners.
- Parameters:
- frame: input frame of type numpy.array
- Returns:
- Case 1:
- None : Returns if no marker detected
- Case 2:
- marker_corners : Returns Corners of detected Aruco Marker
- Case 3:
- “None” : Returns a string, if goes out of region of interest
-
estimate_pose
(marker_corners, frame_of_ref='camera')¶ Estimates the pose of the transform matrix using large ArUco tag.
- Parameters:
- marker_corners: list of marker corners
frame_of_ref: frame of reference. Default value is “camera” - Returns:
- 6-DOF pose estimate of aruco marker in world frame
-
estimate_uncalib_pose
(marker_corners)¶ Returns attitude of Aruco to estimate initial yaw (used by calibrate_yaw() method).
- Parameters:
- marker_corners: corners of the detected aruco tag
- Returns:
- uncalib_rot: returns attitude of Aruco
-
extract_depth
(frame)¶ Returns depth frame from Realsense Depth Camera.
- Parameters:
- frame
- Returns:
- depth frame
-
extract_rgb
(frame)¶ Extracts RGB frame from Realsense RGB Camera.
- Parameters:
- frame
- Returns:
- frame.get_color_frame(): colour frame
-
find_area
(corners)¶ Utility function to find area of the quadrilateral using corner data.
- Parameters:
- corners: co-ordinate of the corners whose area needs to be calculated
- Returns:
- area: returns area of the quadrilateral, specified by its corners
-
get_frames
()¶ Returns the aligned depth and rgb frames for proper depth detection.
- Parameters:
- None
- Returns:
- aligned frames: Returns frame with depth and RGB frame aligned.
-
init_aruco_detector
()¶ Initializes camera Intrinsic and Extrinsic Parameters and generates Aruco detector parameters.
- Parameters:
- None
- Returns:
- None
-
init_realsense
()¶ Initializes Realsense by enabling both depth and RGB stream and sets up parameters such as sharpness, contrast, exposure etc.
- Parameter:
- None
- Returns:
- None
-
make_tf_matrix
(rvec, tvec)¶ Creates the transormation matrix using the rotation and translational vectors.
- Parameters:
- rvec: contains rotational vectors tvec: contains trsnslational vectors
- Returns:
- tf: transformation matrix for the camera
-
outformat_to_tf
(input)¶ Converts the list to the transformation matrix.
- Parameters:
- out_vec: conversion of the transformation matrix into list
- Returns:
- tf: transformation matrix
-
plot_markers
(frame, marker_corners, marker_ids)¶ Draws lines around the detected frames.
- Parameters:
- frame: RGB frame
marker_corners: corners of the detected aruco tag
marker_ids: ids of the detected markers - Returns:
- frame with plotted markers
-
plot_rej_markers
(frame, marker_corners)¶ Draws lines around the detected frames.
- Parameters:
- frame: RGB frame
marker_corners: corners of the detected aruco tag - Returns:
- frame: frame with plotted rejected markers
-
show_frame
(frame, rgb_frame, window_name='Frame')¶ Displays frame for debugging purpose.
- Parameters:
- frame: edited RGB Frame with texts
rgb_frame: original RGB Frame
window_name: name of the window where the frame is displayed - Returns:
- None
-
stop
()¶ Stops the pipeline.
- Parameters:
- None
- Returns:
- None
-
tf_to_outformat
(tf)¶ Converts the transformation matrix to a list.
- Parameters:
- tf: transformation matrix
- Returns:
- out_vec: conversion of the transformation matrix into list
-
to_image
(frame)¶ Converts pyrealsense2.frame to np.array.
- Parameters:
- frame: input frame of type pyrealsense2.frame
- Returns:
- np.asarray(frame.get_data())
-
update_waypoint
(waypoint)¶ Updates the waypoint that is plotted on the image frame to be displayed.
- Parameters:
- waypoint: this is the new waypoint to be updated