@@ -69,10 +69,11 @@ async def main():
69
69
import asyncio
70
70
import socket
71
71
from mavsdk import System
72
- from mavsdk .offboard import AccelerationNed , Attitude , OffboardError , PositionNedYaw , VelocityBodyYawspeed , VelocityNedYaw
72
+ import mavsdk
73
+ from mavsdk .offboard import AccelerationNed , Attitude , OffboardError , PositionGlobalYaw , PositionNedYaw , VelocityBodyYawspeed , VelocityNedYaw
73
74
from control_packet import ControlPacket , SetpointMode # Ensure this import matches your setup
74
75
75
- UDP_IP = "127 .0.0.1 "
76
+ UDP_IP = "0 .0.0.0 "
76
77
UDP_PORT = 5005
77
78
BUFFER_SIZE = 1024 # Adjust based on expected packet size
78
79
@@ -148,6 +149,44 @@ async def handle_packet(drone, packet):
148
149
thrust = control_packet .attitude [3 ] # Ensure thrust is a value between 0 and 1
149
150
print (f"Setting ATTITUDE setpoint: Roll={ roll } °, Pitch={ pitch } °, Yaw={ yaw } °, Thrust={ thrust } " )
150
151
await drone .offboard .set_attitude (Attitude (roll , pitch , yaw , thrust ))
152
+ if control_packet .setpoint_flags & SetpointMode .POSITION_VELOCITY_ACCELERATION_NED .value :
153
+ position = PositionNedYaw (control_packet .position [0 ], control_packet .position [1 ], control_packet .position [2 ], control_packet .attitude [2 ])
154
+ velocity = VelocityNedYaw (control_packet .velocity [0 ], control_packet .velocity [1 ], control_packet .velocity [2 ], control_packet .attitude_rate [2 ])
155
+ acceleration = AccelerationNed (control_packet .acceleration [0 ], control_packet .acceleration [1 ], control_packet .acceleration [2 ])
156
+ print (f"Sending POSITION_VELOCITY_ACCELERATION_NED setpoint: Position { position } , Velocity { velocity } , Acceleration { acceleration } " )
157
+ await drone .offboard .set_position_velocity_acceleration_ned (position , velocity , acceleration )
158
+ if control_packet .setpoint_flags & SetpointMode .POSITION_GLOBAL_LATLON .value :
159
+ lat = control_packet .position [0 ]
160
+ lon = control_packet .position [1 ]
161
+ alt = control_packet .position [2 ]
162
+ yaw = control_packet .attitude [2 ]
163
+ altitude_type = mavsdk .offboard .AltitudeType .AMSL # Choose based on your requirements: AGL or AMSL or REL_HOME
164
+
165
+ print (f"Sending POSITION_GLOBAL_LATLON setpoint: Latitude { lat } , Longitude { lon } , Altitude { alt } , Yaw { yaw } " )
166
+ await drone .offboard .set_position_global (PositionGlobalYaw (lat , lon , alt , yaw , altitude_type ))
167
+ if control_packet .setpoint_flags & SetpointMode .ACCELERATION_NED .value :
168
+ # Extract acceleration values from the packet
169
+ north_acc = control_packet .acceleration [0 ]
170
+ east_acc = control_packet .acceleration [1 ]
171
+ down_acc = control_packet .acceleration [2 ]
172
+ print (f"Setting NED acceleration: North { north_acc } m/s², East { east_acc } m/s², Down { down_acc } m/s²" )
173
+ await drone .offboard .set_acceleration_ned (
174
+ AccelerationNed (north_m_s2 = north_acc , east_m_s2 = east_acc , down_m_s2 = down_acc )
175
+ )
176
+ # Check for velocity NED setpoint
177
+ if control_packet .setpoint_flags & SetpointMode .VELOCITY_NED .value :
178
+ north_vel = control_packet .velocity [0 ]
179
+ east_vel = control_packet .velocity [1 ]
180
+ down_vel = control_packet .velocity [2 ]
181
+ yaw = control_packet .attitude [2 ] # Assuming yaw is stored in the attitude tuple
182
+
183
+ print (f"Setting NED velocity: North { north_vel } , East { east_vel } , Down { down_vel } , Yaw { yaw } " )
184
+ await drone .offboard .set_velocity_ned (
185
+ VelocityNedYaw (north_m_s = north_vel , east_m_s = east_vel , down_m_s = down_vel , yaw_deg = yaw )
186
+ )
187
+
188
+
189
+
151
190
152
191
else :
153
192
is_active = await drone .offboard .is_active ()
0 commit comments