Skip to content

Commit

Permalink
modules: add chat module
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 authored and peterbarker committed Dec 13, 2023
1 parent 10d20f9 commit 4193c54
Show file tree
Hide file tree
Showing 16 changed files with 1,080 additions and 0 deletions.
60 changes: 60 additions & 0 deletions MAVProxy/modules/mavproxy_chat/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
'''
AI Chat Module
Randy Mackay, December 2023
This module allows MAVProxy to interface with OpenAI Assitants
OpenAI Assistant API: https://platform.openai.com/docs/api-reference/assistants
OpenAI Assistant Playground: https://platform.openai.com/playground
MAVProxy chat wiki: https://ardupilot.org/mavproxy/docs/modules/chat.html
'''

from MAVProxy.modules.lib import mp_module
from MAVProxy.modules.lib import mp_util
from MAVProxy.modules.mavproxy_chat import chat_window
from threading import Thread

class chat(mp_module.MPModule):
def __init__(self, mpstate):

# call parent class
super(chat, self).__init__(mpstate, "chat", "OpenAI chat support")

# register module and commands
self.add_command('chat', self.cmd_chat, "chat module", ["show"])

# keep reference to mpstate
self.mpstate = mpstate

# run chat window in a separate thread
self.thread = Thread(target=self.create_chat_window)
self.thread.start()

# create chat window (should be called from a new thread)
def create_chat_window(self):
if mp_util.has_wxpython:
# create chat window
self.chat_window = chat_window.chat_window(self.mpstate)
else:
print("chat: wx support required")

# show help on command line options
def usage(self):
return "Usage: chat <show>"

# control behaviour of the module
def cmd_chat(self, args):
if len(args) == 0:
print(self.usage())
elif args[0] == "show":
self.show()
else:
print(self.usage())

# show chat input window
def show(self):
self.chat_window.show()

# initialise module
def init(mpstate):
return chat(mpstate)
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
You are a helpful assistant that helps users control unmanned vehicles running the ArduPilot software.

You should limit your responses to questions and commands that related to ArduPilot and controlling the vehicle. If the user asks unrelated questions or ask you to compare ArduPilot with other systems, please reply with a statement of your main purpose and suggest they speak with a more general purpose AI (e.g. ChatGPT).

You are configured to be able to control several types of ArduPilot vehicles including Copters, Planes, Rovers, Boats and Submarines.

Copter includes all multicopters (quadcopters, hexacopters, bi-copter, octacopter, octaquad, dodecahexa-copter). Traditional Helicopters are also controlled in the same ways as Copters.

Planes includes all fixed wing vehicles including normal planes and quadplanes. Quadplanes are planes that can also fly like multicopters but they use Plane modes that start with "Q" (e.g. QAltHold)

Rovers (aka cars) and Boats are controlled in the same way.

Each type of vehicle (e.g. Copter, Plane, Rover) has different flight modes (Rovers flight modes are often just called "modes" because they can't fly). Each flight mode has a number and name. The mapping between flight mode name and flight mode number is different for each vehicle type and can be found within the appropriately named copter_flightmodes.txt, plane_flightmodes.txt, rover_modes.txt and sub_modes.txt files.

Users normally specify the flight mode using its name. To change the vehicle's flight mode you will need to send a mavlink command_int message (with "command" field set to MAV_CMD_DO_SET_MODE, 176) and include the flight mode number. Param1, the "Mode" field should be set to 1 (e.g. MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) and the flight mode number should be placed in param2, the "Custom Mode" field. The vehicle's mode can be changed at any time including when it is disarmed.

If the user specifically asks to change the vehicle's flight mode you should do it immediately regardless of any other conditions.

Normally you can only control a vehicle when it is in Guided mode and armed. When asked to move the vehicle (e.g. takeoff, fly to a specific location, etc) you should first check that the vehicle is in Guided mode and armed. If it is not then you should ask the user if it is OK to change to Guided mode and arm the vehicle.

For Copters and Planes, after being armed in Guided mode, the user will normally ask that the vehicle takeoff. You can command the vehicle to takeoff by sending a mavlink command_int message (e.g. MAV_CMD_NAV_TAKEOFF). The desired altitude should be placed in "z" field (aka "Altitude" aka "Param7" field)

To move the vehicle to a specified location send a SET_POSITION_TARGET_GLOBAL_INT message. Be careful to set the "coordinate_frame" field depending upon the desired altitude type (e.g. amsl (relative to sea level), relative to home, or relative to terrain). If you are given or can calculate a target latitude, longitude and altitude then these values should be placed in the "lat_int", "lon_int" and "alt" fields respectively. Also be careful to set the "type_mask" field to match which types of targets are being provided (e.g. position target, velocity targets, yaw target).

If a user is not clear about the altitude type then it is normally safe to assume they mean altitude above home. Sometimes "altitude above home" is referred to as "relative altitude".

The short form of "altitude" is "alt".
The short form of "latitude" is "lat".
The short form of "longitude" is "lat".
The words "position" and "location" are often used synonymously.

Rovers and Boats cannot control their altitude
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
This file holds the Copter flight mode name to number mapping

STABILIZE = 0, // pilot directly controls the airframe angle with roll, pitch and yaw stick inputs. Pilot directly controls throttle
ACRO = 1, // pilot directly controls the body-frame angular rate. pilot directly controls throttle
ALT_HOLD = 2, // pilot directly controls the vehicle roll, pitch and yaw angles. Pilot's throttle control controls climb rate
AUTO = 3, // fully automatic waypoint control using mission commands
GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using mavlink commands.
LOITER = 5, // pilot controls the vehicle's 3D speed and acceleration with roll, pitch and throttle input. Heading is controlled with the yaw stick
RTL = 6, // automatic return to launching point
CIRCLE = 7, // automatic circular flight with automatic throttle
LAND = 9, // automatic landing with horizontal position control
DRIFT = 11, // semi-autonomous position, yaw and throttle control. rarely used.
SPORT = 13, // manual earth-frame angular rate control with manual throttle. very rarely used
FLIP = 14, // automatically flip the vehicle 360 degrees
AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle. very similar to Loiter mode
BRAKE = 17, // full-brake using inertial/GPS system, no pilot input
THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input
AVOID_ADSB = 19, // automatic avoidance of manned vehicle. very rarely used
GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude commands
SMART_RTL = 21, // SMART_RTL returns vehicle home by retracing its steps
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder. similar to Loiter. very rarely used
FOLLOW = 23, // follow attempts to follow another vehicle or ground station
ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B. Normally used for crop spraying vehicles.
SYSTEMID = 25, // System ID mode produces automated system identification signals in the controllers. very rarely used
AUTOROTATE = 26, // Autonomous autorotation. Used only for traditional helicopters
AUTO_RTL = 27, // return to launch but using an Auto mission starting from the DO_LAND_START command
TURTLE = 28, // Flip vehicle to recover after crash

Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
{
"type": "function",
"function": {
"name": "get_current_datetime",
"description": "Get the current date and time, e.g. 'Saturday, June 24, 2023 6:14:14 PM'",
"parameters": {
"type": "object",
"properties": {},
"required": []
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
{
"type": "function",
"function": {
"name": "get_vehicle_location_and_yaw",
"description": "Get the vehicle's current location including latitude, longitude, altitude above sea level and altitude above home",
"parameters": {
"type": "object",
"properties": {
"latitude": {"type": "number", "description": "latitude in degrees"},
"longitude": {"type": "number", "description": "longitude in degrees"},
"altitude_amsl": {"type": "number", "description": "altitude above sea level in meters (aka AMSL)"},
"altitude_above_home": {"type": "number", "description": "altitude above home in meters"},
"yaw": {"type": "number", "description": "vehicle yaw (aka heading) in degrees"}
},
"required": []
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
{
"type": "function",
"function": {
"name": "get_vehicle_state",
"description": "Get the vehicle state including armed status and (flight) mode",
"parameters": {
"type": "object",
"properties": {
"armed": {"type": "boolean", "description": "vehicle armed status. True means motors can spin and vehicle can move."},
"mode": {"type": "number", "description": "flight flight mode. The number is specific to the vehicle type (e.g. Copter, Plane, Rover"}
},
"required": []
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
{
"type": "function",
"function": {
"name": "get_vehicle_type",
"description": "Get the vehicle type (e.g. Copter, Plane, Rover, Boat, etc)",
"parameters": {
"type": "object",
"properties": {
"vehicle_type": {"type": "string", "description": "the vehicle type. Unknown if not known"}
},
"required": []
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
This file holds the Plane flight mode name to number mapping. Modes starting with Q are only for use with QuadPlanes.

MANUAL = 0, // pilot has direct control over servos without stabilization
CIRCLE = 1, // Circle around a GPS waypoint
STABILIZE = 2, // Level flight stabilization
TRAINING = 3, // Limits the roll and pitch angles to keep the aircraft stable
ACRO = 4, // Full manual aerobatic control with some stabilization
FLY_BY_WIRE_A = 5, // Stabilized flight with manual throttle
FLY_BY_WIRE_B = 6, // More stabilization than FLY_BY_WIRE_A
CRUISE = 7, // Mixed manual and automatic throttle control
AUTOTUNE = 8, // Automatically tune the PID controller for optimal performance
AUTO = 10, // Fully autonomous flight, following a pre-programmed mission
RTL = 11, // Return to Launch point
LOITER = 12, // Circle around a point while maintaining altitude
TAKEOFF = 13, // Automated takeoff sequence
AVOID_ADSB = 14, // Avoidance maneuver triggered by ADS-B aircraft detection
GUIDED = 15, // Remotely guided commands from GCS or companion computer
INITIALISING = 16, // Initialization mode at startup
QSTABILIZE = 17, // QuadPlane's stabilize mode. Similar to Copter's stabilize mode
QHOVER = 18, // QuadPlane's hover mode. Similar to Copter's AltHold mode
QLOITER = 19, // QuadPlane's loiter mode. Similar to Copter's Loiter mode
QLAND = 20, // QuadPlane's land mode. Similar to Copter's Land mode
QRTL = 21, // QuadPlane's Return to Launch mode. Similar to Copter's RTL mode
QAUTOTUNE = 22, // QuadPlane's autotune mode. Similar to Copter's AutoTune mode
QACRO = 23, // QuadPlane's acrobatic mode. Similar to Copter's Acro mode
THERMAL = 24, // Thermal detection and exploitation mode
LOITER_ALT_QLAND = 25, // QuadPlane's loiter to alt then land mode

16 changes: 16 additions & 0 deletions MAVProxy/modules/mavproxy_chat/assistant_setup/rover_modes.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
This file holds the Rover (aka car) and boat mode name to number mapping. Rover "modes" are the same as "flight modes" for other vehicles. "Rover" is synonymous with "car"

MANUAL = 0, // Pilot directly controls the vehicle's steering and throttle
ACRO = 1, // Pilot controls the turn rate and speed
STEERING = 3, // Pilot controls the steering using lateral acceleration. throttle stick controls speed
HOLD = 4, // motor and steering outputs are disabled. Rovers will stop, boats will drift in this mode
LOITER = 5, // hold position at the current location
FOLLOW = 6, // follow a GPS-enabled device
SIMPLE = 7, // Pilot controls the vehicles by moving the combined steering and throttle stick in the direction they wish to move. The direction of movement is relative to the vehicle's heading when first powered on
DOCK = 8, // Automatic docking mode
CIRCLE = 9, // Circle around a location recorded when the vehicle entered this mode
AUTO = 10, // Fully autonomous mode following pre-programmed waypoints
RTL = 11, // Return to Launch point
SMART_RTL = 12, // Creates a path back to the launch point based on the rover's traveled path
GUIDED = 15, // Guided control via a ground station or companion computer
INITIALISING = 16, // Initialization mode at startup
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
{
"type": "function",
"function": {
"name": "send_mavlink_command_int",
"description": "Send a mavlink COMMAND_INT message to the vehicle. Available commands including changing the flight mode, arming, disarming, takeoff and commanding the vehicle to fly to a specific location",
"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"},
"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"},
"autocontinue": {"type": "integer", "description": "not used. always zero"},
"param1": {"type": "number", "description": "parameter 1. see MAV_CMD enum"},
"param2": {"type": "number", "description": "parameter 2. see MAV_CMD enum"},
"param3": {"type": "number", "description": "parameter 3. see MAV_CMD enum"},
"param4": {"type": "number", "description": "parameter 4. see MAV_CMD enum"},
"x": {"type": "integer", "description": "latitude in degrees * 10^7"},
"y": {"type": "integer", "description": "longitude in degrees * 10^7"},
"z": {"type": "number", "description": "altitude in meters (relative to sea level, home or terrain depending on frame field)."}
},
"required": ["frame", "command"]
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
{
"type": "function",
"function": {
"name": "send_mavlink_set_position_target_global_int",
"description": "Send a mavlink SET_POSITION_TARGET_GLOBAL_INT message to the vehicle. This message is the preferred way to command a vehicle to fly to a specified location or to fly at a specfied velocity",
"parameters": {
"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"},
"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"},
"lon_int": {"type": "integer", "description": "longitude in degrees * 10^7"},
"alt": {"type": "number", "description": "altitude in meters (relative to sea level, home or terrain depending on frame field)"},
"vx": {"type": "number", "description": "velocity North in m/s"},
"vy": {"type": "number", "description": "velocity East in m/s"},
"vz": {"type": "number", "description": "velocity Down in m/s"},
"afx": {"type": "number", "description": "acceleration North in m/s/s. rarely used, normally 0"},
"afy": {"type": "number", "description": "acceleration East in m/s/s. rarely used, normally 0"},
"afz": {"type": "number", "description": "acceleration Down in m/s/s. rarely used, normally 0"},
"yaw": {"type": "number", "minimum":-6.28318530717959, "maximum":6.28318530717959, "description": "yaw (aka heading) in radians"},
"yaw_rate": {"type": "number", "description": "yaw (aka heading) rotation rate in radians/second. rarely used, normally 0"}
},
"required": ["coordinate_frame", "type_mask"]
}
}
}
Loading

0 comments on commit 4193c54

Please sign in to comment.