drone controller velocity update

This commit is contained in:
2026-01-09 20:21:36 +00:00
parent 79c77fce9e
commit 433e97beb8

View File

@@ -307,28 +307,56 @@ class DroneController:
return False return False
def takeoff(self, altitude=5.0): def takeoff(self, altitude=5.0):
"""Takeoff to altitude.""" """Takeoff to altitude using velocity commands (works in GUIDED_NOGPS)."""
print(f"[INFO] Taking off to {altitude}m...") print(f"[INFO] Taking off to {altitude}m...")
self.mav.mav.command_long_send( # In GUIDED_NOGPS, we can't use NAV_TAKEOFF (requires position estimate)
self.mav.target_system, # Instead, send climb velocity commands
self.mav.target_component, climb_rate = 1.0 # m/s upward
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
0, 0, 0, 0, 0, 0, 0, altitude
)
# Wait for altitude start_time = time.time()
for i in range(100): # 10 seconds max timeout = 30 # seconds
while time.time() - start_time < timeout:
self.update_state() self.update_state()
if self.altitude > altitude * 0.9:
print(f"[OK] Reached {self.altitude:.1f}m") if self.altitude >= altitude * 0.95:
# Stop climbing, hover
self._send_velocity(0, 0, 0)
print(f"\n[OK] Reached {self.altitude:.1f}m")
return True return True
print(f"\r Climbing... {self.altitude:.1f}m", end="")
# Send climb command (negative vz = up in NED)
self._send_velocity(0, 0, -climb_rate)
print(f"\r Climbing... {self.altitude:.1f}m / {altitude:.1f}m", end="")
time.sleep(0.1) time.sleep(0.1)
# Stop any motion
self._send_velocity(0, 0, 0)
print(f"\n[WARN] Takeoff timeout at {self.altitude:.1f}m") print(f"\n[WARN] Takeoff timeout at {self.altitude:.1f}m")
return False return False
def _send_velocity(self, vx, vy, vz, yaw_rate=0):
"""Send velocity command in body frame."""
# Use SET_POSITION_TARGET_LOCAL_NED with velocity only
# type_mask: ignore position, acceleration, yaw (use velocity only)
type_mask = (
0b0000_0001_11_000_111 # Ignore pos (0-2), accel (6-8), yaw (10), use vel (3-5) and yaw_rate (11)
)
self.mav.mav.set_position_target_local_ned_send(
0, # time_boot_ms (ignored)
self.mav.target_system,
self.mav.target_component,
mavutil.mavlink.MAV_FRAME_BODY_NED, # Body frame
type_mask,
0, 0, 0, # Position (ignored)
vx, vy, vz, # Velocity
0, 0, 0, # Acceleration (ignored)
0, yaw_rate # Yaw, yaw_rate
)
def goto(self, x, y, z): def goto(self, x, y, z):
"""Go to position (NED frame, z is down so negative = up).""" """Go to position (NED frame, z is down so negative = up)."""
print(f"[INFO] Going to ({x:.1f}, {y:.1f}, alt={-z:.1f}m)...") print(f"[INFO] Going to ({x:.1f}, {y:.1f}, alt={-z:.1f}m)...")