8 if __name__ ==
'__main__':
9 rospy.init_node(
'test_high_level')
13 cf.setParam(
"commander/enHighLevel", 1)
14 cf.setParam(
"stabilizer/estimator", 2)
15 cf.setParam(
"stabilizer/controller", 2)
18 cf.setParam(
"kalman/resetEstimation", 1)
29 traj1.loadcsv(
"takeoff.csv")
32 traj2.loadcsv(
"figure8.csv")
36 cf.uploadTrajectory(0, 0, traj1)
37 cf.uploadTrajectory(1, len(traj1.polynomials), traj2)
39 cf.startTrajectory(0, timescale=1.0)
40 time.sleep(traj1.duration * 2.0)
42 cf.startTrajectory(1, timescale=2.0)
43 time.sleep(traj2.duration * 2.0)
45 cf.startTrajectory(0, timescale=1.0, reverse=
True)
46 time.sleep(traj1.duration * 1.0)