.. _tutorial_obs_avoidance: Obstacle Avoidance in Outdoor Environment ================================================== **Note: This tutorial is applicable for Kerloud 600 Vision** .. image:: ../img/obs_avoidance/avoidance_gzclient_snap.png :height: 500 px :width: 750 px :scale: 100 % :align: center Obstacle avoidance capability in outdoor environment enables a UAV to fly around unforeseen objects during mission planning, which is a commonly required feature for surveillance, landscape mapping, etc. This functionality is implemented in the onboard companion computer as a standalone software. The official repository for obstacle avoidance can be found in https://github.com/PX4/PX4-Avoidance. However, since the repository has not been updated for a long time, it is not practical for users to deploy it directly for real flight. Environment Setup ------------------------ The Kerloud 600 vision configuration is equipped with a Nvidia Jetson Nano compuater and an Intel Realsense D435i camera. The obstacle avoidance software is prepared under the workspace ~/src/uav_space/catkinws_avoidance. We have tested the code thoroughly during factory to ensure the complete suite works properly. The supported OS is Ubuntu 18.04 with ROS melodic. The avoidance package is delivered in the **dev_kerlouduav** branch, so be sure to switch to that branch to avoid potential software bugs. How to Use ------------- Simulation Test ^^^^^^^^^^^^^^^^^^^ The simulation test can only be performed in a personal computer instead of the companion computer. Assuming that the px4 firmware is located in ~/Firmware with default v1.10.0 version, users can start the simulation with the following commands: :: # Open a terminal, and build the sitl target for px4 firmware sudo apt install ros-melodic-gazebo-ros* # necessary for gazebo ros interface cd ~/Firmware # This is necessary to prevent some Qt-related errors (feel free to try to omit it) export QT_X11_NO_MITSHM=1 # Build and run simulation make px4_sitl_default gazebo Then the local planner can be started in this manner: :: # open a terminal (terminal 1) cd ~/src/uav_space/catkinws_avoidance source devel/setup.bash # add environment setting . ~/Firmware/Tools/setup_gazebo.bash ~/Firmware ~/Firmware/build/px4_sitl_default export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:~/Firmware roslaunch local_planner local_planner_stereo.launch # open another terminal to view image (terminal 2) cd ~/src/uav_space/catkinws_avoidance source devel/setup.bash rosrun image_view stereo_view stereo:=/stereo image:=image_rect_color # open another terminal (terminal 3) rosrun mavros mavsys mode -c OFFBOARD rosrun mavros mavsafety arm Users can then set nav goal by pressing 2D nav button and double clicking in the rviz interface. .. image:: ../img/obs_avoidance/avoidance_localplanner_view2.png :height: 500 px :width: 750 px :scale: 100 % :align: center The global planner can be brought up similarly as the local planner case. :: # open a terminal (terminal 1) cd ~/src/uav_space/catkinws_avoidance source devel/setup.bash # add environment setting . ~/Firmware/Tools/setup_gazebo.bash ~/Firmware ~/Firmware/build/px4_sitl_default export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:~/Firmware roslaunch global_planner global_planner_stereo.launch # open another terminal (terminal 2) rosrun mavros mavsys mode -c OFFBOARD rosrun mavros mavsafety arm .. image:: ../img/obs_avoidance/avoidance_globalplanner_snap.png :height: 500 px :width: 750 px :scale: 100 % :align: center .. hint:: The local planner is recommended by the official guide, which supports higher speed (3m/s) than the global planner (1.5m/s).