ORB_SLAM3 with DJI Tello in Gazebo
Yuang Du (ucab190@ucl.ac.uk)
This project is to simulate DJI Tello drone in Gazebo to perform simultaneous localization and mapping (SLAM) using ORB_SLAM3.
Mono SLAM:
Ape comparison w/wo scale alignment from evo
└── tello_slam_gazebo/
├── src
│ ├── [hector_gazebo](git@github.com:alstondu/hector_quadrotor.git)
│ ├── [hector_localization](git@github.com:alstondu/hector_localization.git)
│ ├── [hector_quadrotor](git@github.com:alstondu/hector_quadrotor.git)
│ ├── [orb_slam3_ros](git@github.com:alstondu/orb_slam3_ros.git)
│ └── [tello_ros_gazebo](git@github.com:alstondu/tello_ros_gazebo.git)
├── media
├── LICENSE
└── README.md
See prerequisites of each submodule.
Submodule | Employed system |
---|---|
Gazebo plugins support | hector_gazebo |
TF and localization support | hector_localization |
Quadrotor controller support | hector_quadrotor |
Visual SLAM | orb_slam3_ros |
Tello model and discription | tello_ros_gazebo |
To evaluate the trajectory obtained, evo is required.
git clone --recursive git@github.com:alstondu/tello_slam_gazebo.git
cd tello_slam_gazebo
catkin build
Tip
source the workspace in each terminal before entering the command.
Launch the system in terminal 1:
roslaunch tello_driver tello.launch
Run teleop node in terminal 2:
rosrun keyboard_teleop keyboard_teleop_node.py _repeat_rate:=10.0
Before driving the drone, in terminal 3, record the predicted trajectory(
/orb_slam3_ros/camera_pose
) and the ground truth(/ground_truth/state
) as rosbag:
rosbag record /orb_slam3_ros/camera_pose /ground_truth/state
Convert the saved rosbag to tum format:
evo_traj bag [bag_name] /orb_slam3_ros/camera_pose /ground_truth/state --save_as_tum
Change the suffix of the files from
.tum
to.txt
, plot the trajectories with(-a
for alignment,-as
for alignment and scale):
evo_traj tum orb_slam3_ros_camera_pose.txt --ref ground_truth_state.txt -a -p --plot_mode=xyz
For APE (Absolute Pose Error), run:
evo_ape tum ground_truth_state.txt orb_slam3_ros_camera_pose.txt -vas -r full -p --plot_mode=xyz
Camera Calibration
Launch the world with the calibration board and the tello in terminal 1:
roslaunch tello_driver cam_cal.launch
Run the keyboard teleop node in terminal 2:
roslaunch tello_driver keyboard_teleop_node.launch
Run cam_calibration node:
rosrun camera_calibration cameracalibrator.py --size 7x7 --square 0.25 image:=/front_cam/camera/image camera:=/front_cam
Drive the drone around the board until
X, Y, Size, Skew
all turn green. Click on the 'CALIBRATE' button, 'Save' the parameters and exit with 'COMMIT'.
LICENSE: MIT. See LICENSE.txt
DISCLAIMER:
THIS INFORMATION AND/OR SOFTWARE IS PROVIDED BY THE AUTHOR "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS INFORMATION AND/OR SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.