From 3d893850c76e69cb5e461598fc95af864687e789 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 30 Dec 2023 10:44:55 +0900 Subject: [PATCH 1/2] chat: send command default sysid fix --- MAVProxy/modules/mavproxy_chat/chat_openai.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/MAVProxy/modules/mavproxy_chat/chat_openai.py b/MAVProxy/modules/mavproxy_chat/chat_openai.py index fb2b735c96..9c2c306a6b 100644 --- a/MAVProxy/modules/mavproxy_chat/chat_openai.py +++ b/MAVProxy/modules/mavproxy_chat/chat_openai.py @@ -475,7 +475,7 @@ def get_location_plus_offset(self, arguments): # send a mavlink command_int message to the vehicle def send_mavlink_command_int(self, arguments): - target_system = arguments.get("target_system", 1) + target_system = arguments.get("target_system", self.mpstate.settings.target_system) target_component = arguments.get("target_component", 1) frame = arguments.get("frame", 0) if ("command" not in arguments): @@ -519,7 +519,7 @@ def send_mavlink_set_position_target_global_int(self, arguments): if arguments is None: return "send_mavlink_set_position_target_global_int: arguments is None" time_boot_ms = arguments.get("time_boot_ms", 0) - target_system = arguments.get("target_system", 1) + target_system = arguments.get("target_system", self.mpstate.settings.target_system) target_component = arguments.get("target_component", 1) coordinate_frame = arguments.get("coordinate_frame", 5) type_mask = arguments.get("type_mask", 0) From 2f0a2bf43703ad8c42b4e3c3263422ecda776343 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 30 Dec 2023 14:07:01 +0900 Subject: [PATCH 2/2] chat: assistant functions omit target sysid and compid --- .../assistant_setup/send_mavlink_command_int.json | 4 ++-- .../send_mavlink_set_position_target_global_int.json | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_command_int.json b/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_command_int.json index 6fb73aa2be..5ba4e640f1 100644 --- a/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_command_int.json +++ b/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_command_int.json @@ -6,8 +6,8 @@ "parameters": { "type": "object", "properties": { - "target_system": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot System ID. normally 1"}, - "target_component": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot Component ID. normally 1"}, + "target_system": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot System ID. can be omitted"}, + "target_component": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot Component ID. can be omitted"}, "frame": {"type": "integer", "minimum":0, "maximum":21, "description": "altitude type. see MAV_FRAME. 0 for altitude above sea level, 3 for altitude above home, 10 for altitude above terrain"}, "command": {"type": "integer", "minimum":0, "maximum":65535, "description": "MAVLink command id. See MAV_CMD for a full list of available commands"}, "current": {"type": "integer", "description": "not used. always zero"}, diff --git a/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_set_position_target_global_int.json b/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_set_position_target_global_int.json index 5ba91e1643..05cb2fdc55 100644 --- a/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_set_position_target_global_int.json +++ b/MAVProxy/modules/mavproxy_chat/assistant_setup/send_mavlink_set_position_target_global_int.json @@ -7,8 +7,8 @@ "type": "object", "properties": { "time_boot_ms": {"type": "integer", "description": "system timestamp. can be left as 0"}, - "target_system": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot System ID. normally 1"}, - "target_component": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot Component ID. normally 1"}, + "target_system": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot System ID. can be omitted"}, + "target_component": {"type": "integer", "minimum":0, "maximum":255, "description": "vehicle autopilot Component ID. can be omitted"}, "coordinate_frame": {"type": "integer", "minimum":0, "maximum":21, "description": "altitude type. see MAV_FRAME. 5 for altitude above sea level, 6 for altitude above home, 11 for altitude above terrain"}, "type_mask": {"type": "integer", "minimum":0, "maximum":65535, "description": "Bitmap to indicate which dimensions should be ignored by the vehicle. see POSITION_TARGET_TYPEMASK. If location (e.g. lat_int, lon_int and alt) are sent use 3576. If a location (e.g. lat_int, lon_int and alt) and yaw are sent use 2552. If velocity (e.g. vx, vy, vz) is sent use 2552. if velocity (e.g. vx, vy, vz) and yaw are sent use 2503. If only yaw is sent use 2559"}, "lat_int": {"type": "integer", "description": "latitude in degrees * 10^7"},