-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathfixedwing.py
More file actions
189 lines (142 loc) · 6.1 KB
/
fixedwing.py
File metadata and controls
189 lines (142 loc) · 6.1 KB
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
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
#!/usr/bin/env python
import rospy
import numpy as np
from std_msgs.msg import *
from mavros_msgs.msg import *
from mavros_msgs.srv import *
from geometry_msgs.msg import Point, PoseStamped
from math import atan2, asin, cos, sin, pi
class FCU:
def __init__(self):
rospy.init_node('mc_node', anonymous=True) # name of this node
self.rate = rospy.Rate(20.0)
# pub/sub
self.pixhawk_sp_pub = rospy.Publisher('mavros/setpoint_position/local', PoseStamped, queue_size=1)
self.local_pos_pub = rospy.Publisher('drone/local_pos', Point, queue_size = 1)
rospy.Subscriber('mavros/state', State, self.state_cb)
rospy.Subscriber('mavros/local_position/pose', PoseStamped, self.local_pose_cb)
rospy.Subscriber('mavros/extended_state', ExtendedState, self.extended_state_cb)
# services
self.flightModeService = rospy.ServiceProxy('mavros/set_mode', mavros_msgs.srv.SetMode)
self.takeoffService = rospy.ServiceProxy('mavros/cmd/takeoff', mavros_msgs.srv.CommandTOL)
self.landingService = rospy.ServiceProxy('mavros/cmd/land', mavros_msgs.srv.CommandTOL)
self.armService = rospy.ServiceProxy('mavros/cmd/arming', mavros_msgs.srv.CommandBool)
# variables
self.current_state = State()
self.current_state.connected = 0
self.pixhawk_pose = PoseStamped()
self.pixhawk_sp = PoseStamped()
self.local_pos_int = 0
self.local_pos = Point(0, 0, 0)
self.local_pos0 = Point(0, 0, 0)
self.local_sp = Point(0, 0, 0)
self.extended_state = ExtendedState()
# connect to pixhawk
self.connect()
pass
def takeoff(self):
self.arm()
while ((self.extended_state.landed_state == 1) or (+10.0 > self.local_pos.z)):
rospy.wait_for_service('mavros/cmd/takeoff')
# self.takeoffService(min_pitch = 15.0, altitude = 30.0, yaw = 0.0)
self.takeoffService(altitude = 30.0, yaw = 90.0)
rospy.loginfo("Taking off, %d", self.extended_state.landed_state)
self.rate.sleep()
def land(self):
# would probably not want to put inside a while loop
while (self.extended_state.landed_state != 1):
rospy.wait_for_service('mavros/cmd/landing')
self.landingService(min_pitch = 0.0, altitude = 30.0, yaw = 90.0)
rospy.loginfo("Landing off")
self.rate.sleep()
def arm(self):
while (self.current_state.armed == False):
rospy.wait_for_service('mavros/cmd/arming')
self.armService(True)
self.rate.sleep()
# rospy.loginfo("ARMED: %d", self.current_state.armed)
def disarm(self):
while (self.current_state.armed == True):
rospy.wait_for_service('mavros/cmd/arming')
self.armService(False)
self.rate.sleep()
rospy.loginfo("ARMED: %d", self.current_state.armed)
def connect(self):
timeout = 100.0
t_s = rospy.get_time()
while ((rospy.is_shutdown != 0) and (self.current_state.connected == False)):
rospy.loginfo("Connecting...")
if (rospy.get_time() - t_s > timeout):
break
self.rate.sleep()
if (self.current_state.connected == True):
rospy.loginfo("Pixhawk connected")
else:
rospy.loginfo("Failed to connect")
def setOffboardMode(self):
self.arm()
rospy.wait_for_service('mavros/set_mode')
self.flightModeService(custom_mode = 'OFFBOARD')
def offboardModeSetup(self):
self.pixhawk_sp.pose.position.x = 0
self.pixhawk_sp.pose.position.y = 0
self.pixhawk_sp.pose.position.z = 30
# set offboard mode
for cnt in range (0,100):
self.pixhawk_sp_pub.publish(self.pixhawk_sp)
self.rate.sleep()
for cnt in range (0,10):
self.setOffboardMode()
self.rate.sleep()
def state_cb(self, msg):
self.current_state = msg
def extended_state_cb(self, msg):
self.extended_state = msg
def local_pose_cb(self, msg):
self.pixhawk_pose = msg
if (self.local_pos_int == 0):
self.local_pos0.x = self.pixhawk_pose.pose.position.x
self.local_pos0.y = self.pixhawk_pose.pose.position.y
self.local_pos0.z = self.pixhawk_pose.pose.position.z
self.local_pos_int = 1
self.local_pos.x = self.pixhawk_pose.pose.position.x - self.local_pos0.x
self.local_pos.y = self.pixhawk_pose.pose.position.y - self.local_pos0.y
self.local_pos.z = self.pixhawk_pose.pose.position.z - self.local_pos0.z
def setWaypoint(self, local_sp, yaw_d):
self.pixhawk_sp.pose.position.x = local_sp.x + self.local_pos0.x
self.pixhawk_sp.pose.position.y = local_sp.y + self.local_pos0.y
self.pixhawk_sp.pose.position.z = local_sp.z + self.local_pos0.z
if (yaw_d > 180.0):
yaw_d = (-yaw_d - 90.0)*pi/180.0
self.pixhawk_sp.pose.orientation.w = -sin(yaw_d/2)
self.pixhawk_sp.pose.orientation.x = 0
self.pixhawk_sp.pose.orientation.y = 0
self.pixhawk_sp.pose.orientation.z = cos(yaw_d/2)
else:
yaw_d = (-yaw_d - 90.0)*pi/180.0
self.pixhawk_sp.pose.orientation.w = sin(yaw_d/2)
self.pixhawk_sp.pose.orientation.x = 0
self.pixhawk_sp.pose.orientation.y = 0
self.pixhawk_sp.pose.orientation.z = -cos(yaw_d/2)
self.pixhawk_sp_pub.publish(self.pixhawk_sp)
self.local_pos_pub.publish(self.local_pos)
def main():
fcu = FCU()
fcu.arm()
fcu.offboardModeSetup()
fcu.takeoff()
timeout = 30.0
t_s = rospy.get_time()
local_sp = Point(100.0, 100.0, 50.0)
yaw_d = 90.0
while (timeout > rospy.get_time() - t_s):
fcu.setOffboardMode()
fcu.setWaypoint(local_sp, yaw_d)
fcu.rate.sleep()
fcu.land()
fcu.disarm()
if __name__ == '__main__':
try:
main()
except rospy.ROSInterruptException:
pass