aboutsummaryrefslogtreecommitdiff
path: root/integrationtests/demo_tests/direct_offboard_posctl_test.py
blob: af8d4b821bd4eef0c2eef08ec6b5d985a94920eb (plain) (blame)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
#!/usr/bin/env python
PKG = 'px4'

import sys
import unittest
import rospy

from numpy import linalg
import numpy as np

from px4.msg import vehicle_local_position
from px4.msg import vehicle_control_mode
from px4.msg import actuator_armed
from px4.msg import position_setpoint_triplet
from px4.msg import position_setpoint
from sensor_msgs.msg import Joy
from std_msgs.msg import Header

from manual_input import ManualInput
from flight_path_assertion import FlightPathAssertion


class OffboardPosctlTest(unittest.TestCase):

	def setUp(self):
		rospy.init_node('test_node', anonymous=True)
		rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
		rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
		self.pubSpt = rospy.Publisher('px4_multicopter/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
		self.rate = rospy.Rate(10) # 10hz

	#
	# General callback functions used in tests
	#
	def position_callback(self, data):
		self.hasPos = True
		self.localPosition = data

	def vehicle_control_mode_callback(self, data):
		self.controlMode = data


	#
	# Helper methods
	#
	def is_at_position(self, x, y, z, offset):
		rospy.logdebug("current position %f, %f, %f" % (self.localPosition.x, self.localPosition.y, self.localPosition.z))
		desired = np.array((x, y, z))
		pos = np.array((self.localPosition.x, self.localPosition.y, self.localPosition.z))
		return linalg.norm(desired - pos) < offset

	def reach_position(self, x, y, z, timeout):
		# set a position setpoint
		pos = position_setpoint()
		pos.valid = True
		pos.x = x
		pos.y = y
		pos.z = z
		pos.position_valid = True
		stp = position_setpoint_triplet()
		stp.current = pos
		self.pubSpt.publish(stp)

		# does it reach the position in X seconds?
		count = 0
		while(count < timeout):
			if(self.is_at_position(pos.x, pos.y, pos.z, 0.5)):
				break
			count = count + 1
			self.rate.sleep()

		self.assertTrue(count < timeout, "took too long to get to position")

	#
	# Test offboard POSCTL
	#
	def test_posctl(self):
		manIn = ManualInput()

		# arm and go into offboard
		manIn.arm()
		manIn.offboard()
		self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set")
		self.assertTrue(self.controlMode.flag_control_offboard_enabled, "flag_control_offboard_enabled is not set")
		self.assertTrue(self.controlMode.flag_control_position_enabled, "flag_control_position_enabled is not set")
	
		# prepare flight path assertion
		fpa = FlightPathAssertion(
			(
				(0,0,0),
				(2,2,-2),
				(2,-2,-2),
				(-2,-2,-2),
				(2,2,-2),
			), 0.5, 0)
		fpa.start()

		self.reach_position(2, 2, -2, 120)
		self.reach_position(2, -2, -2, 120)
		self.reach_position(-2, -2, -2, 120)
		self.reach_position(2, 2, -2, 120)
		
		# does it hold the position for Y seconds?
		positionHeld = True
		count = 0
		timeout = 50
		while(count < timeout):
			if(not self.is_at_position(2, 2, -2, 0.5)):
				positionHeld = False
				break
			count = count + 1
			self.rate.sleep()

		self.assertTrue(count == timeout, "position could not be held")
		fpa.stop()
	

if __name__ == '__main__':
	import rostest
	rostest.rosrun(PKG, 'posctl_test', OffboardPosctlTest)
	#unittest.main()