Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Chat: improved feedback, parameter get/set and get latest mavlink support #1286

Merged
merged 5 commits into from
Dec 20, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -34,3 +34,7 @@ The short form of "longitude" is "lat".
The words "position" and "location" are often used synonymously.

Rovers and Boats cannot control their altitude

Parameters on the vehicle hold many settings that affect how the vehicle behaves. When responding to users requests to get or set parameter values be sure to check the vehicle specific parameter definition files (e.g. copter_parameter_definitions.xml, plane_parameter_definitions.xml, rover_parameter_definitions.xml, sub_parameter_definitions.xml) to ensure the correct units are used.

Before any action is taken to set or get vehicle parameters, be sure you know the vehicle type. The easiest way to do this may be to call the get_vehicle_type function. Once you know the vehicle type, the vehicle specific parameter definition file must be accessed and read to confirm the correct parameter names and the expected data types and units. For copters refer to the copter_parameter_definitions.xml file, for planes refer to plane_parameter_definitions.xml, for rovers and boats refer to rover_parameter_definitions.xml, and for subs (aka submarines) refer to sub_parameter_definitions.xml. If the file cannot be found or accessed, please report to the user that the parameter definitions file is required before proceeding. Once the file is accessed, utilize the parameter information within it to validate parameter names and units against any user request for setting or getting vehicle parameter values. Perform the requested action (set or get) only if the parameter definitions have been successfully verified to match the request.
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
{
"type": "function",
"function": {
"name": "get_all_parameters",
"description": "Get all available parameter names and values",
"parameters": {
"type": "object",
"properties": {},
"required": []
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
{
"type": "function",
"function": {
"name": "get_available_mavlink_messages",
"description": "Get a list of mavlink message names that can be retrieved using the get_mavlink_message function",
"parameters": {
"type": "object",
"properties": {},
"required": []
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
{
"type": "function",
"function": {
"name": "get_mavlink_message",
"description": "Get a mavlink message including all fields and values sent by the vehicle. The list of available messages can be retrieved using the get_available_mavlink_messages",
"parameters": {
"type": "object",
"properties": {
"message": {"type": "string", "description": "mavlink message name (e.g. HEARTBEAT, VFR_HUD, GLOBAL_POSITION_INT, etc)"}
},
"required": ["message"]
}
}
}
15 changes: 15 additions & 0 deletions MAVProxy/modules/mavproxy_chat/assistant_setup/get_parameter.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
{
"type": "function",
"function": {
"name": "get_parameter",
"description": "Get a vehicle parameter's value. The full list of available parameters and their values is available using the get_all_parameters function",
"parameters": {
"type": "object",
"properties": {
"name": {"type": "string", "description": "parameter name (e.g. ARMING_CHECK, LOG_BITMASK). Regex expressions are supported"},
"value": {"type": "number", "description": "parameter value"}
},
"required": ["name"]
}
}
}
15 changes: 15 additions & 0 deletions MAVProxy/modules/mavproxy_chat/assistant_setup/set_parameter.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
{
"type": "function",
"function": {
"name": "set_parameter",
"description": "Set a vehicle parameter's value. The full list of parameters is available using the get_all_parameters function",
"parameters": {
"type": "object",
"properties": {
"name": {"type": "string", "description": "parameter name (e.g. ARMING_CHECK, LOG_BITMASK)"},
"value": {"type": "number", "description": "parameter value"}
},
"required": ["name", "value"]
}
}
}
18 changes: 15 additions & 3 deletions MAVProxy/modules/mavproxy_chat/assistant_setup/setup_assistant.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,18 @@ def main(openai_api_key=None, assistant_name=None, model_name=None, upgrade=Fals
if not download_file("https://raw.githubusercontent.com/ArduPilot/mavlink/master/message_definitions/v1.0/" + mavlink_filename, mavlink_filename):
exit()

# download latest vehicle parameter definition files from ardupilot server
paramdef_file_info = [
{"url": "https://autotest.ardupilot.org/Parameters/ArduCopter/apm.pdef.xml", "filename": "copter_parameter_definitions.xml"},
{"url": "https://autotest.ardupilot.org/Parameters/ArduPlane/apm.pdef.xml", "filename": "plane_parameter_definitions.xml"},
{"url": "https://autotest.ardupilot.org/Parameters/APMrover2/apm.pdef.xml", "filename": "rover_parameter_definitions.xml"},
{"url": "https://autotest.ardupilot.org/Parameters/ArduSub/apm.pdef.xml", "filename": "sub_parameter_definitions.xml"}]
paramdef_filenames = []
for pdef_file_info in paramdef_file_info:
if not download_file(pdef_file_info["url"], pdef_file_info["filename"]):
exit()
paramdef_filenames.append(pdef_file_info["filename"])

# variable to hold new assistant
assistant = None

Expand Down Expand Up @@ -116,11 +128,11 @@ def main(openai_api_key=None, assistant_name=None, model_name=None, upgrade=Fals
print("setup_assistant: failed to update assistant instructions")
exit()

# upload MAVLink and text files
# upload MAVLink, text and parameter definition files
# get our organisation's existing list of files on OpenAI
existing_files = client.files.list()
uploaded_file_ids = []
for filename in text_filenames + mavlink_filenames:
for filename in text_filenames + mavlink_filenames + paramdef_filenames:
try:
# open local file as read-only
file = open(filename, 'rb')
Expand Down Expand Up @@ -156,7 +168,7 @@ def main(openai_api_key=None, assistant_name=None, model_name=None, upgrade=Fals
exit()

# delete downloaded mavlink files
for mavlink_filename in mavlink_filenames:
for mavlink_filename in mavlink_filenames + paramdef_filenames:
try:
os.remove(mavlink_filename)
print("setup_assistant: deleted local file: " + mavlink_filename)
Expand Down
167 changes: 164 additions & 3 deletions MAVProxy/modules/mavproxy_chat/chat_openai.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
'''

from pymavlink import mavutil
import time
import time, re
from datetime import datetime
import json
import math
Expand All @@ -20,10 +20,13 @@
exit()

class chat_openai():
def __init__(self, mpstate):
def __init__(self, mpstate, status_cb=None):
# keep reference to mpstate
self.mpstate = mpstate

# keep reference to status callback
self.status_cb = status_cb

# initialise OpenAI connection
self.client = None
self.assistant = None
Expand Down Expand Up @@ -123,9 +126,12 @@ def send_to_assistant(self, text):
self.handle_function_call(latest_run)
run_done = False
else:
print ("chat: unrecognised run status" + latest_run.status)
print("chat: unrecognised run status" + latest_run.status)
run_done = True

# send status to status callback
self.send_status(latest_run.status)

# retrieve messages on the thread
reply_messages = self.client.beta.threads.messages.list(self.assistant_thread.id, order = "asc", after=input_message.id)
if reply_messages is None:
Expand Down Expand Up @@ -216,6 +222,52 @@ def handle_function_call(self, run):
except:
print("chat: send_mavlink_set_position_target_global_int: failed to parse arguments")


# get a list of mavlink message names that can be retrieved using the get_mavlink_message function
if tool_call.function.name == "get_available_mavlink_messages":
recognised_function = True
output = self.get_available_mavlink_messages()

# get mavlink message from vehicle
if tool_call.function.name == "get_mavlink_message":
recognised_function = True
try:
arguments = json.loads(tool_call.function.arguments)
output = self.get_mavlink_message(arguments)
except:
output = "get_mavlink_message: failed to retrieve message"
print("chat: get_mavlink_message: failed to retrieve message")

# get all parameters from vehicle
if tool_call.function.name == "get_all_parameters":
recognised_function = True
try:
arguments = json.loads(tool_call.function.arguments)
output = self.get_all_parameters(arguments)
except:
output = "get_all_parameters: failed to retrieve parameters"
print("chat: get_all_parameters: failed to retrieve parameters")

# get a vehicle parameter's value
if tool_call.function.name == "get_parameter":
recognised_function = True
try:
arguments = json.loads(tool_call.function.arguments)
output = self.get_parameter(arguments)
except:
output = "get_parameter: failed to retrieve parameter value"
print("chat: get_parameters: failed to retrieve parameter value")

# set a vehicle parameter's value
if tool_call.function.name == "set_parameter":
recognised_function = True
try:
arguments = json.loads(tool_call.function.arguments)
output = self.set_parameter(arguments)
except:
output = "set_parameter: failed to set parameter value"
print("chat: set_parameter: failed to set parameter value")

if not recognised_function:
print("chat: handle_function_call: unrecognised function call: " + tool_call.function.name)
output = "unrecognised function call: " + tool_call.function.name
Expand Down Expand Up @@ -366,6 +418,102 @@ def send_mavlink_set_position_target_global_int(self, arguments):
self.mpstate.master().mav.set_position_target_global_int_send(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)
return "set_position_target_global_int sent"

# get a list of mavlink message names that can be retrieved using the get_mavlink_message function
def get_available_mavlink_messages(self):
# check if no messages available
if self.mpstate.master().messages is None or len(self.mpstate.master().messages) == 0:
return "get_available_mavlink_messages: no messages available"

# retrieve each available message's name
mav_msg_names = []
for msg in self.mpstate.master().messages:
# append all message names except MAV
if msg != "MAV":
mav_msg_names.append(msg)

# return list of message names
try:
return json.dumps(mav_msg_names)
except:
return "get_available_mavlink_messages: failed to convert message name list to json"

# get a mavlink message including all fields and values sent by the vehicle
def get_mavlink_message(self, arguments):
if arguments is None:
return "get_mavlink_message: arguments is None"

# retrieve requested message's name
mav_msg_name = arguments.get("message", None)
if mav_msg_name is None:
return "get_mavlink_message: message not specified"

# retrieve message
mav_msg = self.mpstate.master().messages.get(mav_msg_name, None)
if mav_msg is None:
return "get_mavlink_message: message not found"

# convert message to json
try:
return json.dumps(mav_msg.to_dict())
except:
return "get_mavlink_message: failed to convert message to json"

# get all available parameters names and their values
def get_all_parameters(self, arguments):
# check if any parameters are available
if self.mpstate.mav_param is None or len(self.mpstate.mav_param) == 0:
return "get_all_parameters: no parameters are available"
param_list = {}
for param_name in sorted(self.mpstate.mav_param.keys()):
param_list[param_name] = self.mpstate.mav_param.get(param_name)
try:
return json.dumps(param_list)
except:
return "get_all_parameters: failed to convert parameter list to json"

# get a vehicle parameter's value
def get_parameter(self, arguments):
param_name = arguments.get("name", None)
if param_name is None:
print("get_parameter: name not specified")
return "get_parameter: name not specified"

# start with empty parameter list
param_list = {}

# handle param name containing regex
if self.contains_regex(param_name):
pattern = re.compile(param_name)
for existing_param_name in sorted(self.mpstate.mav_param.keys()):
if pattern.match(existing_param_name) is not None:
param_value = self.mpstate.functions.get_mav_param(existing_param_name, None)
if param_value is None:
print("chat: get_parameter unable to get " + existing_param_name)
else:
param_list[existing_param_name] = param_value
else:
# handle simple case of a single parameter name
param_value = self.mpstate.functions.get_mav_param(param_name, None)
if param_value is None:
return "get_parameter: " + param_name + " parameter not found"
param_list[param_name] = param_value

try:
return json.dumps(param_list)
except:
return "get_parameter: failed to convert parameter list to json"

# set a vehicle parameter's value
def set_parameter(self, arguments):
param_name = arguments.get("name", None)
if param_name is None:
return "set_parameter: parameter name not specified"
param_value = arguments.get("value", None)
if param_value is None:
return "set_parameter: value not specified"
self.mpstate.functions.param_set(param_name, param_value, retries=3)
return "set_parameter: parameter value set"

# wrap latitude to range -90 to 90
def wrap_latitude(self, latitude_deg):
if latitude_deg > 90:
Expand All @@ -381,3 +529,16 @@ def wrap_longitude(self, longitude_deg):
if longitude_deg < -180:
return longitude_deg + 360
return longitude_deg

# send status to chat window via callback
def send_status(self, status):
if self.status_cb is not None:
self.status_cb(status)

# returns true if string contains regex characters
def contains_regex(self, string):
regex_characters = ".^$*+?{}[]\|()"
for x in regex_characters:
if string.count(x):
return True
return False
12 changes: 11 additions & 1 deletion MAVProxy/modules/mavproxy_chat/chat_window.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ def __init__(self, mpstate):
self.send_lock = Lock()

# create chat_openai object
self.chat_openai = chat_openai.chat_openai(self.mpstate)
self.chat_openai = chat_openai.chat_openai(self.mpstate, self.set_status_text)

# create chat_voice_to_text object
self.chat_voice_to_text = chat_voice_to_text.chat_voice_to_text()
Expand Down Expand Up @@ -65,9 +65,13 @@ def __init__(self, mpstate):
# add a reply box and read-only text box
self.text_reply = wx.TextCtrl(self.frame, id=-1, size=(600, 80), style=wx.TE_READONLY | wx.TE_MULTILINE)

# add a read-only status text box at the bottom
self.text_status = wx.TextCtrl(self.frame, id=-1, size=(600, -1), style=wx.TE_READONLY)

# set size hints and add sizer to frame
self.vert_sizer.Add(self.horiz_sizer, proportion=0, flag=wx.EXPAND)
self.vert_sizer.Add(self.text_reply, proportion=1, flag=wx.EXPAND, border=5)
self.vert_sizer.Add(self.text_status, proportion=0, flag=wx.EXPAND, border=5)
self.frame.SetSizer(self.vert_sizer)

# show frame
Expand Down Expand Up @@ -114,12 +118,14 @@ def record_button_click_execute(self, event):
rec_filename = self.chat_voice_to_text.record_audio()
if rec_filename is None:
print("chat: audio recording failed")
self.set_status_text("Audio recording failed")
return

# convert audio to text and place in input box
text = self.chat_voice_to_text.convert_audio_to_text(rec_filename)
if text is None:
print("chat: audio to text conversion failed")
self.set_status_text("Audio to text conversion failed")
return
wx.CallAfter(self.text_input.SetValue, text)

Expand Down Expand Up @@ -164,3 +170,7 @@ def send_text_to_assistant(self):
wx.CallAfter(self.record_button.Enable)
wx.CallAfter(self.text_input.Enable)
wx.CallAfter(self.send_button.Enable)

# set status text
def set_status_text(self, text):
wx.CallAfter(self.text_status.SetValue, text)