Camera Aruco Tags Dectection
This commit is contained in:
@@ -26,6 +26,14 @@ GUIDED_MODE = 4
|
||||
GUIDED_NOGPS_MODE = 20
|
||||
|
||||
|
||||
DEFAULT_WPNAV_SPEED = 150
|
||||
DEFAULT_WPNAV_ACCEL = 100
|
||||
DEFAULT_WPNAV_SPEED_UP = 100
|
||||
DEFAULT_WPNAV_SPEED_DN = 75
|
||||
DEFAULT_WPNAV_ACCEL_Z = 75
|
||||
DEFAULT_LOIT_SPEED = 150
|
||||
|
||||
|
||||
class Controller:
|
||||
|
||||
HOLD_ALT = HOLD_ALT
|
||||
@@ -277,9 +285,31 @@ class Controller:
|
||||
print("\n[UAV] GPS timeout")
|
||||
return False
|
||||
|
||||
def configure_speed_limits(self,
|
||||
wpnav_speed=DEFAULT_WPNAV_SPEED,
|
||||
wpnav_accel=DEFAULT_WPNAV_ACCEL,
|
||||
wpnav_speed_up=DEFAULT_WPNAV_SPEED_UP,
|
||||
wpnav_speed_dn=DEFAULT_WPNAV_SPEED_DN,
|
||||
wpnav_accel_z=DEFAULT_WPNAV_ACCEL_Z,
|
||||
loit_speed=DEFAULT_LOIT_SPEED):
|
||||
|
||||
params = {
|
||||
'WPNAV_SPEED': wpnav_speed,
|
||||
'WPNAV_ACCEL': wpnav_accel,
|
||||
'WPNAV_SPEED_UP': wpnav_speed_up,
|
||||
'WPNAV_SPEED_DN': wpnav_speed_dn,
|
||||
'WPNAV_ACCEL_Z': wpnav_accel_z,
|
||||
'LOIT_SPEED': loit_speed,
|
||||
}
|
||||
for name, value in params.items():
|
||||
self.set_param(name, value)
|
||||
print(f"[UAV] Speed limits set: horiz={wpnav_speed}cm/s "
|
||||
f"accel={wpnav_accel}cm/s² up={wpnav_speed_up}cm/s "
|
||||
f"dn={wpnav_speed_dn}cm/s")
|
||||
|
||||
def set_max_velocity(self, speed):
|
||||
self.conn.mav.command_long_send(
|
||||
self.conn.target_system,
|
||||
self.conn.target_component,
|
||||
mavlink.MAV_CMD_DO_CHANGE_SPEED,
|
||||
0, speed, -1, 0, 0, 0, 0, 0)
|
||||
0, 1, speed, -1, 0, 0, 0, 0)
|
||||
|
||||
Reference in New Issue
Block a user