Line Following
In this practical, you will learn how to put together your parameterization of a line detected from the downward camera with a flight controller to accurately follow a line.
Key tools:
opencv
Closed-loop velocity control
rosmsg
SLIDES: Lecture Slides
Progress: Checkpoint Rubric
Breaking Down Line Following
Computer Vision (line_tracker/src/detector.py
)
Your computer vision algorithms must be precise and accurate when detecting the LED strip that will feature in the final race.
Be sure to test your existing CV algorithms by publishing an Image message on /line/img
that shows the line being tracked. You will be testing this on a rosbag
before you have the opportunity to fly your code. Notify an instructor once you have the proper image displayed on top of the rosbag
we have provided you. You will then be permitted to move on to the next stage of development in this task.
Control Systems (line_tracker/src/tracker.py
)
You will be controlling three degrees of freedom in the line following task: \(x position\), \(y position\), and \(yaw\)
Using information about the image that the downward camera is publishing, you will calculate the error between your desired position on the line and your current position.
This can be broken down into a few steps:
Find the point representing the center of the image \(p_{frame-center}\), and take the point on the line published by detector \(p_{line}\) (in pixel coordinates)
Find the unit vector in the direction of the line \(\vec{r}_{line-unit}\) (using
vx
andvy
published by detector)Find the point on the line closest to the center of the frame \(p_{line-closest-center}\)
Extrapolate a point forward (from \(p_{line-closest-center}\)) on the line using the unit vector in the direction of the line, making sure that the unit vector is positive \(p_{target}\)
Calculate the vector from the center of the frame to the extrapolated point (this represents error) \(\vec{r}_{to-target}\) and draw it on the annotated image you are publishing
Use \(\vec{r}_{to-target}\) to calculate x, y, and yaw errors
Select safe, appropriate gains for your proportional velocity controller than enable the drone to change its velocity to track a the target on the line. Should its response be aggressive? Consider the pros and cons of aggressive vs non-aggressive control behavior. Your \(K_{P_x}\), \(K_{P_y}\), \(K_{P_ZW}\) should always start below 1.
Calculate \(v_x(t)\), \(v_y(t)\), and \(v_z(t)\) using your pre-determined \(K_P\) values.
Diagram:
Setup for Test Flight
Once detector.py
and tracker.py
have been completed and pulled onto the drone, run the flight test by following these procedures
Power on remote control
Power on the Intel RTF
Connect to the UAV via QGroundControl
SSH into the UAV (you will need to have at least four terminals SSHed into the UAV). use X-forwarding in order to pass graphics (i.e. stream the camera feed from the drone to your computer). Example replacing
<team-drone-name>
with the name of your drone:ssh -X uav@<team-drone-name>.beaver.works
In terminal 1, start distance sensor
sudo systemctl start aero-teraranger.service
In terminal 1, start ROS
roscore
In terminal 2, start patched optical flow + down-camera streaming. Note: this is different from standard optical flow service that prevents streaming downward-facing camera. Needed for line detection. See here for more info on setting up
cd ~/bwsi-uav/catkin_ws/src/aero-optical-flow/build sudo -E ./aero-optical-flow
Without arming drone, switch to
POSITION CONTROL
mode to ensure previous steps worked as expect. If QGroundControl declares that that position control is rejected, use QGroundControl > Widgets > MAVLink Inspector to debug and potentially restart process.In terminal 3, launch
mavros
,detector
, andtracker
usingdetect_track.launch
cd ~/bwsi-uav/catkin_ws source devel/setup.bash roslaunch aero_control detect_track.launch
(OPTIONAL) In terminal 4, visualize the downward camera feed for line detection.
rqt_image_view
and select
/line/detector_image
from the dropdown menu
Test Flight
WARNING:
Pilot-in-Command must always be ready to regain control by switching back to POSCTL
mode. Never take your hands off the remote control!
In POSITION CONTROL
mode
Arm the quadrotor
Takeoff
Position in a safe location in the air
Switch to
OFFBOARD
mode to run testRegain control with
POSITION
modeLand quadrotor
Disarm
Collect flight log
[ ]: