roscd offboard_py
mkdir launch
cd launch
touch start_offb.launch
Required
- Ubuntu 20.04
- ROS Noetic(ROS 1)
- GAZEBO 11(ROS 설치 시 기본 탑재)
자율주행 드론 제작에 앞서...
드론의 제어 메커니즘을 개발하기 위함이 아닌 자율주행을 가능토록 함에 있으므로 수년간 개발된 PX4를 기반으로 한다.
글쓴이도 드론이나 비행기를 제작할 때 PX4가 탑재된 Pixhawk4를 사용해왔으며 Manual Control이 아닌 자율주행을 구행하기 위해 Companion Computer를 추가적으로 설치하여 진행할 계획이다.
자율주행 드론을 제작하기에 앞서 가상환경에서 알고리즘을 분석하고 적용하는 과정을 선제적으로 진행하려 한다.

시뮬레이션 환경을 구성하기 위해서는
1. 비행 제어 시스템(PX4) - 판단/인지 후 명령 알고리즘
2. 시뮬레이션 환경
으로 크게 나누어 볼 수 있다.
알고리즘 제작에 앞서서 기본적인 환경을 구축하고자 한다.
PX4-Tool Chain 설치
앞에서 말한 바와 같이 비행에 대한 기본 제어 시스템은 PX4를 기반으로 한다. 그러므로 PX4에서 제공중인 Tool Chain을 이용하여 진행할 계획이다.
1. 작업 공간(catkin_ws) 생성
mkdir -p ~/catkin_ws/src
cd catkin_ws/src
catkin_init_workspace
2. GITHUB를 통해 PX4-Autopilot 받아오기
git clone https://github.com/PX4/PX4-Autopilot.git --recursive
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
MAVROS 설치
앞에서 말한 바와 같이 통신 프로토콜은 MAVLink를 통해 이뤄진다. 이때 전달되는 형태는 MAVROS를 기반으로 하고 있다. 그러므로 해당 형태로 통신할 수 있도록 MAVROS를 설치한다.
sudo apt-get install ros-noetic-mavros ros-noetic-mavros-extras
wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh
sudo bash ./install_geographiclib_datasets.sh
cd ~/catkin_ws
source devel/setup.bash
catkin init
wstool init src
rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall
wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src -j4
rosdep install --from-paths src --ignore-src -y
catkin build
기본 예제의 적용
기본적인 Offboard 예제 파일이 PX4 User Guide를 통해 제공된다.
cd catkin_ws/src
catkin_create_pkg offboard_py rospy
cd ..
catkin build
source devel/setup.bash
roscd offboard_py
mkdir scripts
cd scripts
Code
touch offb_node.py
chmod +x offb_node.py
offb_node.py 코드(python3를 이용하므로 python 버전 3으로 설정)
"""
* File: offb_node.py
* Stack and tested in Gazebo Classic 9 SITL
"""
#! /usr/bin/env python3
import rospy
from geometry_msgs.msg import PoseStamped
from mavros_msgs.msg import State
from mavros_msgs.srv import CommandBool, CommandBoolRequest, SetMode, SetModeRequest
current_state = State()
def state_cb(msg):
global current_state
current_state = msg
if __name__ == "__main__":
rospy.init_node("offb_node_py")
state_sub = rospy.Subscriber("mavros/state", State, callback = state_cb)
local_pos_pub = rospy.Publisher("mavros/setpoint_position/local", PoseStamped, queue_size=10)
rospy.wait_for_service("/mavros/cmd/arming")
arming_client = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
rospy.wait_for_service("/mavros/set_mode")
set_mode_client = rospy.ServiceProxy("mavros/set_mode", SetMode)
# Setpoint publishing MUST be faster than 2Hz
rate = rospy.Rate(20)
# Wait for Flight Controller connection
while(not rospy.is_shutdown() and not current_state.connected):
rate.sleep()
pose = PoseStamped()
pose.pose.position.x = 0
pose.pose.position.y = 0
pose.pose.position.z = 2
# Send a few setpoints before starting
for i in range(100):
if(rospy.is_shutdown()):
break
local_pos_pub.publish(pose)
rate.sleep()
offb_set_mode = SetModeRequest()
offb_set_mode.custom_mode = 'OFFBOARD'
arm_cmd = CommandBoolRequest()
arm_cmd.value = True
last_req = rospy.Time.now()
while(not rospy.is_shutdown()):
if(current_state.mode != "OFFBOARD" and (rospy.Time.now() - last_req) > rospy.Duration(5.0)):
if(set_mode_client.call(offb_set_mode).mode_sent == True):
rospy.loginfo("OFFBOARD enabled")
last_req = rospy.Time.now()
else:
if(not current_state.armed and (rospy.Time.now() - last_req) > rospy.Duration(5.0)):
if(arming_client.call(arm_cmd).success == True):
rospy.loginfo("Vehicle armed")
last_req = rospy.Time.now()
local_pos_pub.publish(pose)
rate.sleep()
launch file
roscd offboard_py
mkdir launch
cd launch
touch start_offb.launch
<?xml version="1.0"?>
<launch>
<!-- Include the MAVROS node with SITL and Gazebo -->
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
</include>
<!-- Our node to control the drone -->
<node pkg="offboard_py" type="offb_node.py" name="offb_node_py" required="true" output="screen" />
</launch>
roslaunch offboard_py start_offb.launch
bashrc에 별도로 설정을 하지 않았다면 다음과 같은 오류가 발생한다.
Resource not found: px4
ROS path [0]=/opt/ros/noetic/share/ros
ROS path [1]=/home/inhadrone/catkin_ws/src/mavros/libmavconn
ROS path [2]=/home/inhadrone/catkin_ws/src/mavros/mavros_msgs
ROS path [3]=/home/inhadrone/catkin_ws/src/mavros/mavros
ROS path [4]=/home/inhadrone/catkin_ws/src/mavros/mavros_extras
ROS path [5]=/home/inhadrone/catkin_ws/src/offboard_py
ROS path [6]=/home/inhadrone/catkin_ws/src/mavros/test_mavros
ROS path [7]=/opt/ros/noetic/share
The traceback for the exception was written to the log file
# 터미널에 입력하기
gedit ~/.bashrc
bashrc 파일 하단에 다음 문장을 복사하여 붙여넣자.
px4_dir=~/PX4-Autopilot
source $px4_dir/Tools/simulation/gazebo-classic/setup_gazebo.bash $px4_dir $px4_dir/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$px4_dir
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$px4_dir/Tools/simulation/gazebo-classic/sitl_gazebo-classic
'Learning Space > Autonomous Flight' 카테고리의 다른 글
[ROS1 NOTE] rospy.Rate() (1) | 2023.03.13 |
---|---|
[Autonomous Navigation] Path Planning (0) | 2023.03.10 |
[Autonomous DRONE] PX4 Models Error (0) | 2023.03.07 |
[State Machine] State Machine에 대한 이해 (0) | 2023.01.16 |