diff options
author | Lorenz Meier <lorenz@px4.io> | 2015-03-02 08:31:34 +0100 |
---|---|---|
committer | Lorenz Meier <lorenz@px4.io> | 2015-03-02 08:31:34 +0100 |
commit | 9574c6dd2a2688a12850eaff10c5a1f3ff8d47c3 (patch) | |
tree | 4cdec21d4742a917e93cb341e542af86ff41380a /integrationtests/demo_tests/manual_input.py | |
parent | 48bf84ff3754109fe6cf8e0e161eb70ae0987bfe (diff) | |
parent | 3f8c011e8c05bcfc668bb1aff8b3227c47cf8884 (diff) | |
download | px4-firmware-9574c6dd2a2688a12850eaff10c5a1f3ff8d47c3.tar.gz px4-firmware-9574c6dd2a2688a12850eaff10c5a1f3ff8d47c3.tar.bz2 px4-firmware-9574c6dd2a2688a12850eaff10c5a1f3ff8d47c3.zip |
Merge pull request #1854 from UAVenture/mavros_arming
Mavros test updates
Diffstat (limited to 'integrationtests/demo_tests/manual_input.py')
-rwxr-xr-x | integrationtests/demo_tests/manual_input.py | 14 |
1 files changed, 7 insertions, 7 deletions
diff --git a/integrationtests/demo_tests/manual_input.py b/integrationtests/demo_tests/manual_input.py index 55911bede..cf139bb1d 100755 --- a/integrationtests/demo_tests/manual_input.py +++ b/integrationtests/demo_tests/manual_input.py @@ -45,7 +45,7 @@ from std_msgs.msg import Header # # Manual input control helper # -# Note: this is not the way to do it. ATM it fakes input to iris/command/attitude because else +# FIXME: this is not the way to do it! ATM it fakes input to iris/command/attitude because else # the simulator does not instantiate our controller. # class ManualInput: @@ -74,7 +74,7 @@ class ManualInput: pos.offboard_switch = 3 count = 0 - while not rospy.is_shutdown() and count < 10: + while not rospy.is_shutdown() and count < 5: rospy.loginfo("zeroing") time = rospy.get_rostime().now() pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 @@ -86,7 +86,7 @@ class ManualInput: pos.r = 1 count = 0 - while not rospy.is_shutdown() and count < 10: + while not rospy.is_shutdown() and count < 5: rospy.loginfo("arming") time = rospy.get_rostime().now() pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 @@ -111,7 +111,7 @@ class ManualInput: pos.offboard_switch = 3 count = 0 - while not rospy.is_shutdown() and count < 10: + while not rospy.is_shutdown() and count < 5: rospy.loginfo("triggering posctl") time = rospy.get_rostime().now() pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 @@ -122,7 +122,7 @@ class ManualInput: def offboard(self): rate = rospy.Rate(10) # 10hz - # triggers posctl + # triggers offboard pos = manual_control_setpoint() pos.x = 0 pos.z = 0 @@ -136,8 +136,8 @@ class ManualInput: pos.offboard_switch = 1 count = 0 - while not rospy.is_shutdown() and count < 10: - rospy.loginfo("triggering posctl") + while not rospy.is_shutdown() and count < 5: + rospy.loginfo("triggering offboard") time = rospy.get_rostime().now() pos.timestamp = time.secs * 1e6 + time.nsecs / 1000 self.pubMcsp.publish(pos) |