Skip to content

Commit

Permalink
chat: support get and set parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Dec 17, 2023
1 parent 78f88a7 commit 9c913a5
Showing 1 changed file with 70 additions and 0 deletions.
70 changes: 70 additions & 0 deletions MAVProxy/modules/mavproxy_chat/chat_openai.py
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,36 @@ def handle_function_call(self, run):
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_all_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")

# send mavlink message to vehicle
if tool_call.function.name == "send_mavlink_message":
recognised_function = True
Expand Down Expand Up @@ -470,6 +500,46 @@ def send_mavlink_message(self, arguments):
except:
return "send_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.mav_param is None or len(self.mav_param) == 0:
return "get_all_parameters: no parameters are available"
# get all parameters
param_list = []
for param in self.mav_param:
param_list.append({param.key, param.value})
try:
# print all params
print(param_list)
# convert parameters to json
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"
param_value = self.mpstate.functions.get_mav_param(param_name, None)
if param_value is None:
print("get_parameter: " + param_name + " parameter not found")
return "get_parameter: " + param_name + " parameter not found"
return json.dumps({"name": param_name, "value": param_value})

# 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 Down

0 comments on commit 9c913a5

Please sign in to comment.