|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +import math |
| 4 | +import rospy |
| 5 | +import pytest |
| 6 | +from pytest import approx |
| 7 | +from numpy import isfinite |
| 8 | +from geometry_msgs.msg import PoseStamped |
| 9 | +from mavros_msgs.msg import State |
| 10 | +from sensor_msgs.msg import NavSatFix |
| 11 | +from clever import srv |
| 12 | +from std_srvs.srv import Trigger |
| 13 | + |
| 14 | +import tf2_ros |
| 15 | +import tf2_geometry_msgs |
| 16 | + |
| 17 | +def roughly(expected): |
| 18 | + return pytest.approx(expected, abs=1e-1) |
| 19 | + |
| 20 | +def very_roughly(expected): |
| 21 | + return pytest.approx(expected, abs=1) |
| 22 | + |
| 23 | +@pytest.fixture() |
| 24 | +def node(): |
| 25 | + return rospy.init_node('clever_test', anonymous=True) |
| 26 | + |
| 27 | +def wait_service(name, service_class): |
| 28 | + res = rospy.ServiceProxy(name, service_class) |
| 29 | + res.wait_for_service(5) |
| 30 | + return res |
| 31 | + |
| 32 | +@pytest.fixture |
| 33 | +def get_telemetry(): |
| 34 | + return wait_service('get_telemetry', srv.GetTelemetry) |
| 35 | + |
| 36 | +@pytest.fixture |
| 37 | +def navigate(): |
| 38 | + return wait_service('navigate', srv.Navigate) |
| 39 | + |
| 40 | +@pytest.fixture |
| 41 | +def navigate(): |
| 42 | + res = rospy.ServiceProxy('navigate', srv.Navigate) |
| 43 | + res.wait_for_service(5) |
| 44 | + return res |
| 45 | + |
| 46 | +@pytest.fixture |
| 47 | +def land(): |
| 48 | + return wait_service('land', Trigger) |
| 49 | + |
| 50 | +@pytest.fixture |
| 51 | +def tf_buffer(): |
| 52 | + buf = tf2_ros.Buffer() |
| 53 | + tf2_ros.TransformListener(buf) |
| 54 | + return buf |
| 55 | + |
| 56 | +def wait_connection(): |
| 57 | + start = rospy.get_rostime() |
| 58 | + while rospy.get_rostime() - start <= rospy.Duration(15): |
| 59 | + state = rospy.wait_for_message('mavros/state', State, timeout=10) |
| 60 | + if state.connected: |
| 61 | + return True |
| 62 | + assert False, "no connection to SITL" |
| 63 | + |
| 64 | +def minimal_rate(func, rate): |
| 65 | + start = rospy.get_rostime() |
| 66 | + i = 0 |
| 67 | + while rospy.get_rostime() - start <= rospy.Duration(2): |
| 68 | + func() |
| 69 | + i += 1 |
| 70 | + result_rate = i / 2 |
| 71 | + assert result_rate >= rate, 'Rate too low: %s Hz' % result_rate |
| 72 | + |
| 73 | +def test_state_initial(node): |
| 74 | + wait_connection() |
| 75 | + state = rospy.wait_for_message('mavros/state', State, timeout=10) |
| 76 | + assert state.connected == True |
| 77 | + assert state.armed == False |
| 78 | + |
| 79 | +def test_telem_initial(node, get_telemetry): |
| 80 | + # wait for local position |
| 81 | + rospy.wait_for_message('mavros/local_position/pose', PoseStamped, timeout=15) |
| 82 | + rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=30) |
| 83 | + |
| 84 | + telem = get_telemetry() |
| 85 | + assert telem.frame_id == 'map' |
| 86 | + assert telem.connected == True |
| 87 | + assert telem.armed == False |
| 88 | + assert telem.mode != '' |
| 89 | + assert telem.x == roughly(0.0) |
| 90 | + assert telem.y == roughly(0.0) |
| 91 | + assert telem.z == roughly(0.0) |
| 92 | + assert telem.lat == approx(47.397742) |
| 93 | + assert telem.lon == approx(8.545594) |
| 94 | + assert telem.vx == roughly(0.0) |
| 95 | + assert telem.vy == roughly(0.0) |
| 96 | + assert telem.vz == roughly(0.0) |
| 97 | + assert telem.pitch == roughly(0.0) |
| 98 | + assert telem.roll == roughly(0.0) |
| 99 | + assert telem.yaw == roughly(1.56) |
| 100 | + assert isfinite(telem.voltage) |
| 101 | + assert isfinite(telem.cell_voltage) |
| 102 | + |
| 103 | +def test_telem_rate(node, get_telemetry): |
| 104 | + minimal_rate(lambda: get_telemetry(), 20) |
| 105 | + minimal_rate(lambda: get_telemetry(frame_id='body'), 20) |
| 106 | + minimal_rate(lambda: get_telemetry(frame_id='base_link'), 200) |
| 107 | + |
| 108 | +def test_takeoff_without_auto_arm(node, navigate): |
| 109 | + res = navigate(z=2, frame_id='body') |
| 110 | + assert res.success == False |
| 111 | + assert res.message == 'Copter is not in OFFBOARD mode, use auto_arm?' |
| 112 | + |
| 113 | +def test_takeoff(node, navigate, get_telemetry, tf_buffer): |
| 114 | + res = navigate(z=2, speed=1, frame_id='body', auto_arm=True) |
| 115 | + assert res.success == True, res.message |
| 116 | + rospy.sleep(5) |
| 117 | + telem = get_telemetry() |
| 118 | + assert telem.z == very_roughly(2.0) |
| 119 | + assert telem.x == very_roughly(0.0) |
| 120 | + assert telem.y == very_roughly(0.0) |
| 121 | + assert telem.pitch == roughly(0.0) |
| 122 | + assert telem.roll == roughly(0.0) |
| 123 | + assert telem.yaw == roughly(1.56) |
| 124 | + |
| 125 | +def test_navigate_nans(node, navigate): |
| 126 | + res = navigate(x=float('nan')) |
| 127 | + assert res.success == False |
| 128 | + assert res.message == 'x argument cannot be NaN or Inf' |
| 129 | + res = navigate(y=float('nan')) |
| 130 | + assert res.success == False |
| 131 | + assert res.message == 'y argument cannot be NaN or Inf' |
| 132 | + res = navigate(z=float('nan')) |
| 133 | + assert res.success == False |
| 134 | + assert res.message == 'z argument cannot be NaN or Inf' |
| 135 | + res = navigate(x=float('inf')) |
| 136 | + assert res.success == False |
| 137 | + assert res.message == 'x argument cannot be NaN or Inf' |
| 138 | + res = navigate(y=float('inf')) |
| 139 | + assert res.success == False |
| 140 | + assert res.message == 'y argument cannot be NaN or Inf' |
| 141 | + res = navigate(z=float('inf')) |
| 142 | + assert res.success == False |
| 143 | + assert res.message == 'z argument cannot be NaN or Inf' |
| 144 | + res = navigate(x=float('-inf')) |
| 145 | + assert res.success == False |
| 146 | + assert res.message == 'x argument cannot be NaN or Inf' |
| 147 | + res = navigate(y=float('-inf')) |
| 148 | + assert res.success == False |
| 149 | + assert res.message == 'y argument cannot be NaN or Inf' |
| 150 | + res = navigate(z=float('-inf')) |
| 151 | + assert res.success == False |
| 152 | + assert res.message == 'z argument cannot be NaN or Inf' |
| 153 | + |
| 154 | +def test_navigate(node, navigate, get_telemetry, tf_buffer): |
| 155 | + res = navigate(x=1, y=2, z=3, speed=1) |
| 156 | + assert res.success == True, res.message |
| 157 | + nav_target = tf_buffer.lookup_transform('map', 'navigate_target', rospy.get_rostime(), rospy.Duration(0.2)) |
| 158 | + assert nav_target.transform.translation.x == approx(1) |
| 159 | + assert nav_target.transform.translation.y == approx(2) |
| 160 | + assert nav_target.transform.translation.z == approx(3) |
| 161 | + rospy.sleep(10) |
| 162 | + telem = get_telemetry() |
| 163 | + assert telem.x == very_roughly(1.0) |
| 164 | + assert telem.y == very_roughly(2.0) |
| 165 | + assert telem.z == very_roughly(3.0) |
| 166 | + assert telem.pitch == roughly(0.0) |
| 167 | + assert telem.roll == roughly(0.0) |
| 168 | + assert telem.yaw == roughly(0.0) |
| 169 | + |
| 170 | + res = navigate(x=-1, y=-2, z=-1, frame_id='body', speed=1) |
| 171 | + assert res.success == True, res.message |
| 172 | + nav_target = tf_buffer.lookup_transform('map', 'navigate_target', rospy.get_rostime(), rospy.Duration(0.2)) |
| 173 | + assert nav_target.transform.translation.x == very_roughly(0) |
| 174 | + assert nav_target.transform.translation.y == very_roughly(0) |
| 175 | + assert nav_target.transform.translation.z == very_roughly(2) |
| 176 | + rospy.sleep(10) |
| 177 | + telem = get_telemetry() |
| 178 | + assert telem.x == very_roughly(0) |
| 179 | + assert telem.y == very_roughly(0) |
| 180 | + assert telem.z == very_roughly(2) |
| 181 | + assert telem.pitch == roughly(0) |
| 182 | + assert telem.roll == roughly(0) |
| 183 | + assert telem.yaw == roughly(0) |
| 184 | + |
| 185 | +# TODO |
| 186 | +# test navigate_global, set_velocity, set_attitude, set_rates |
| 187 | + |
| 188 | +def test_land(node, get_telemetry, land): |
| 189 | + res = land() |
| 190 | + assert res.success, res.message |
| 191 | + telem = get_telemetry() |
| 192 | + assert telem.mode == 'AUTO.LAND' |
| 193 | + assert telem.armed == True, 'Drone unexpectedly disarmed while landing' |
| 194 | + rospy.sleep(12) |
| 195 | + telem = get_telemetry() |
| 196 | + assert telem.mode == 'AUTO.LAND' |
| 197 | + assert telem.armed == False, 'Drone is not disarmed after landing' |
0 commit comments