test_high_level.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 import crazyflie
5 import time
6 import uav_trajectory
7 
8 if __name__ == '__main__':
9  rospy.init_node('test_high_level')
10 
11  cf = crazyflie.Crazyflie("crazyflie", "/vicon/crazyflie/crazyflie")
12 
13  cf.setParam("commander/enHighLevel", 1)
14  cf.setParam("stabilizer/estimator", 2) # Use EKF
15  cf.setParam("stabilizer/controller", 2) # Use mellinger controller
16 
17  # reset kalman
18  cf.setParam("kalman/resetEstimation", 1)
19 
20  # cf.takeoff(targetHeight = 0.5, duration = 2.0)
21  # time.sleep(3.0)
22 
23  # cf.goTo(goal = [0.5, 0.0, 0.0], yaw=0.2, duration = 2.0, relative = True)
24  # time.sleep(3.0)
25 
26  # cf.land(targetHeight = 0.0, duration = 2.0)
27 
29  traj1.loadcsv("takeoff.csv")
30 
32  traj2.loadcsv("figure8.csv")
33 
34  print(traj1.duration)
35 
36  cf.uploadTrajectory(0, 0, traj1)
37  cf.uploadTrajectory(1, len(traj1.polynomials), traj2)
38 
39  cf.startTrajectory(0, timescale=1.0)
40  time.sleep(traj1.duration * 2.0)
41 
42  cf.startTrajectory(1, timescale=2.0)
43  time.sleep(traj2.duration * 2.0)
44 
45  cf.startTrajectory(0, timescale=1.0, reverse=True)
46  time.sleep(traj1.duration * 1.0)
47 
48  cf.stop()


crazyflie_demo
Author(s): Wolfgang Hoenig
autogenerated on Mon Sep 28 2020 03:40:12