Go to the documentation of this file.00001
00002
00003 import rospy
00004 import crazyflie
00005 import time
00006 import uav_trajectory
00007
00008 if __name__ == '__main__':
00009 rospy.init_node('test_high_level')
00010
00011 cf = crazyflie.Crazyflie("crazyflie", "/vicon/crazyflie/crazyflie")
00012
00013 cf.setParam("commander/enHighLevel", 1)
00014 cf.setParam("stabilizer/estimator", 2)
00015 cf.setParam("stabilizer/controller", 2)
00016
00017
00018 cf.setParam("kalman/resetEstimation", 1)
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 traj1 = uav_trajectory.Trajectory()
00029 traj1.loadcsv("takeoff.csv")
00030
00031 traj2 = uav_trajectory.Trajectory()
00032 traj2.loadcsv("figure8.csv")
00033
00034 print(traj1.duration)
00035
00036 cf.uploadTrajectory(0, 0, traj1)
00037 cf.uploadTrajectory(1, len(traj1.polynomials), traj2)
00038
00039 cf.startTrajectory(0, timescale=1.0)
00040 time.sleep(traj1.duration * 2.0)
00041
00042 cf.startTrajectory(1, timescale=2.0)
00043 time.sleep(traj2.duration * 2.0)
00044
00045 cf.startTrajectory(0, timescale=1.0, reverse=True)
00046 time.sleep(traj1.duration * 1.0)
00047
00048 cf.stop()