Skip to content

Commit c8f816b

Browse files
committed
receiver listens to all
1 parent c1d5556 commit c8f816b

File tree

3 files changed

+50
-11
lines changed

3 files changed

+50
-11
lines changed

examples/offboard_from_stream/attitude_sender_example.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@
6767
SEND_RATE = 0.1 # Packet send rate in seconds (10 Hz)
6868
ROLL_PITCH_STEP = 2.0 # degrees step for roll and pitch
6969
YAW_RATE_STEP = 5.0 # degrees step for yaw
70-
THRUST_STEP = 0.05 # thrust step
70+
THRUST_STEP = 0.02 # thrust step
7171
INCREMENTAL_MODE = False # False for instant reset, True for incremental control
7272

7373
# Initialize Pygame and set up the display

examples/offboard_from_stream/control_packet.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@
5555
mode=SetpointMode.POSITION_VELOCITY_NED | SetpointMode.YAW_CONTROL,
5656
enable_flag=True,
5757
yaw_control_flag=True,
58-
position=(10.0, 20.0, -5.0),
58+
position=(10.0, 20.0, -5.0), NED: North(m),East,Down(m) | Global: lat(deg),long(deg),alt(m)
5959
velocity=(0.5, 0.5, 0.0),
6060
acceleration=(0.0, 0.0, 0.0),
6161
attitude=(0.0, 0.0, 30.0, 0.6), # Yaw to 30 degrees, 60% thrust
@@ -71,13 +71,13 @@
7171
from enum import Enum
7272

7373
class SetpointMode(Enum):
74-
POSITION_GLOBAL_LATLON = 0x40
75-
POSITION_LOCAL_NED = 0x20
76-
VELOCITY_NED = 0x80
74+
POSITION_GLOBAL_LATLON = 0x40 # Not Tested
75+
POSITION_LOCAL_NED = 0x20
76+
VELOCITY_NED = 0x80 # Not Tested
7777
VELOCITY_BODY = 0x100
78-
POSITION_VELOCITY_NED = 0x01
79-
POSITION_VELOCITY_ACCELERATION_NED = 0x02
80-
ACCELERATION_NED = 0x04
78+
POSITION_VELOCITY_NED = 0x01 # Not Tested
79+
POSITION_VELOCITY_ACCELERATION_NED = 0x02 # Not Tested
80+
ACCELERATION_NED = 0x04 # Not Tested
8181
ATTITUDE_CONTROL = 0x08 # Direct attitude control including thrust
8282
YAW_CONTROL = 0x200 # Separate flag for yaw control
8383

@@ -92,7 +92,7 @@ def __init__(self, mode, enable_flag, yaw_control_flag, position, velocity, acce
9292
self.setpoint_flags = mode.value
9393
self.enable_flag = int(enable_flag) # Ensure enable_flag is integer
9494
self.yaw_control_flag = int(yaw_control_flag) # Ensure yaw_control_flag is integer
95-
self.position = position
95+
self.position = position #NED: North(m),East,Down(m) | Global: lat(deg),long(deg),alt(m)
9696
self.velocity = velocity
9797
self.acceleration = acceleration
9898
self.attitude = attitude

examples/offboard_from_stream/receiver.py

Lines changed: 41 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,10 +69,11 @@ async def main():
6969
import asyncio
7070
import socket
7171
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
7374
from control_packet import ControlPacket, SetpointMode # Ensure this import matches your setup
7475

75-
UDP_IP = "127.0.0.1"
76+
UDP_IP = "0.0.0.0"
7677
UDP_PORT = 5005
7778
BUFFER_SIZE = 1024 # Adjust based on expected packet size
7879

@@ -148,6 +149,44 @@ async def handle_packet(drone, packet):
148149
thrust = control_packet.attitude[3] # Ensure thrust is a value between 0 and 1
149150
print(f"Setting ATTITUDE setpoint: Roll={roll}°, Pitch={pitch}°, Yaw={yaw}°, Thrust={thrust}")
150151
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+
151190

152191
else:
153192
is_active = await drone.offboard.is_active()

0 commit comments

Comments
 (0)