Подключение к симулятору и управление дроном с помощью программы на Питоне
Управление дроном из командной строки Линукс возможно, но довольно трудоёмко. Для выполнения сложных миссий необходимо использовать средства программирования.
Наиболее удобным и простым средством программирования полётных миссий на момент написания учебного пособия является язык Python (по русски - Питон) – современный мультиплатформенный объектно-отриентированный язык программирования. Разработка языка осуществляется сообществом python.org.
В данном разделе мы приведём пример программы на Питоне для управления виртуальным коптером с помощью клавиш клавиатуры: вперёд/назад/влево/вправо, u-вверх, d-вниз, q-выход из программы.
Ниже приведён листинг программы:
#!/usr/bin/env python
import rospy
import mavros
import mavros.command as mc
from mavros_msgs.msg import State
from geometry_msgs.msg import PoseStamped
from mavros_msgs.srv import CommandBool
from mavros_msgs.srv import SetMode
current_state=State()
# keyboard manipulation
import curses
stdscr = curses.initscr()
curses.noecho()
stdscr.nodelay(1)
stdscr.keypad(1)
def state_callback(data):
global current_state
current_state=data
def setpoint_callback(data):
pass
def main():
rospy.init_node("offbrd",anonymous=True)
rate=rospy.Rate(20)
state=rospy.Subscriber("/mavros/state",State,state_callback)
setpoint_sub=rospy.Subscriber("/mavros/setpoint_position/local",PoseStamped,setpoint_callback)
setpoint_pub=rospy.Publisher("/mavros/setpoint_position/local",PoseStamped,queue_size=10)
arming_s=rospy.ServiceProxy("/mavros/cmd/arming",CommandBool)
set_mode=rospy.ServiceProxy("/mavros/set_mode",SetMode)
setpt=PoseStamped()
setpt.pose.position.x=0
setpt.pose.position.y=0
setpt.pose.position.z=2
arming_s(True)
for i in range (0,100):
setpoint_pub.publish(setpt)
rate.sleep()
set_mode(0,"OFFBOARD")
last_request=rospy.Time.now()
cnt = 1
while (rospy.is_shutdown()==False):
if (current_state.mode!="OFFBOARD" and (rospy.Time.now() - last_request > rospy.Duration(5.0))):
print "OFFBOARD lost!!!!!!!!!!!!!!!!!!!!!"
if(set_mode(0,"OFFBOARD")==True):
print("offboard enabled")
last_request=rospy.Time.now()
else:
if (current_state.armed!=True and (rospy.Time.now() - last_request > rospy.Duration(5.0))):
if(mc.arming(True)):
print ("armed")
last_request=rospy.Time.now()
cnt = cnt+1
setpoint_pub.publish(setpt)
rate.sleep()
# keyboard hcommands handling
c = stdscr.getch()
if c == ord('q'): break # Exit the while()
elif c == ord('u'): setpt.pose.position.z += 1
elif c == ord('d'): setpt.pose.position.z -= 1
elif c == curses.KEY_LEFT:setpt.pose.position.y += 1
elif c == curses.KEY_RIGHT:setpt.pose.position.y -= 1
elif c == curses.KEY_UP:setpt.pose.position.x += 1
elif c == curses.KEY_DOWN:setpt.pose.position.x -= 1
if c!=curses.ERR: print setpt.pose.position
if __name__=="__main__":
main()
curses.endwin()
Текст программы нужно записать сохранить в виде текстового файла и запустить с помощью команды python <имя файла>.
После запуска программы виртуальный дрон зависнет на высоте 2 метра и дальше будет подчиняться командам оператора с клавиатуры.