Skip to content
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
138 changes: 100 additions & 38 deletions gcs/src/components/config/radioCalibration.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -5,35 +5,36 @@
*/

// Base imports
import { useEffect } from "react"

// Styling imports
import resolveConfig from "tailwindcss/resolveConfig"
import tailwindConfig from "../../../tailwind.config"
import { useEffect, useMemo } from "react"

// Helper javascript files
import { Progress } from "@mantine/core"
import { Checkbox, Progress, Select, Table } from "@mantine/core"
import apmParamDefsCopter from "../../../data/gen_apm_params_def_copter.json"
import apmParamDefsPlane from "../../../data/gen_apm_params_def_plane.json"

// Redux
import { useDispatch, useSelector } from "react-redux"
import {
emitGetRcConfig,
selectRadioChannels,
emitSetRcConfigParam,
selectRadioChannelsConfig,
selectRadioPwmChannels,
} from "../../redux/slices/configSlice"
import {
emitSetState,
selectConnectedToDrone,
} from "../../redux/slices/droneConnectionSlice"
import { selectAircraftType } from "../../redux/slices/droneInfoSlice"
import { selectAircraftTypeString } from "../../redux/slices/droneInfoSlice"

// Tailwind
// Styling imports
import resolveConfig from "tailwindcss/resolveConfig"
import tailwindConfig from "../../../tailwind.config"
const tailwindColors = resolveConfig(tailwindConfig).theme.colors

const PWM_MIN = 800
const PWM_MAX = 2200
const colors = [

const COLOURS = [
tailwindColors.red[500],
tailwindColors.orange[500],
tailwindColors.yellow[500],
Expand All @@ -52,17 +53,50 @@ function getPercentageValueFromPWM(pwmValue) {
export default function RadioCalibration() {
const dispatch = useDispatch()
const connected = useSelector(selectConnectedToDrone)
const aircraftType = useSelector(selectAircraftType)
const channels = useSelector(selectRadioChannels)
const aircraftTypeString = useSelector(selectAircraftTypeString)
const pwmChannels = useSelector(selectRadioPwmChannels)
const channelsConfig = useSelector(selectRadioChannelsConfig)

function getReadableRcOption(option) {
if (option === 0) return null
if (aircraftType === 1) {
return apmParamDefsPlane.RC5_OPTION.Values[`${option}`] ?? option
} else if (aircraftType === 2) {
return apmParamDefsCopter.RC5_OPTION.Values[`${option}`] ?? option
}
const paramDefs = useMemo(() => {
return aircraftTypeString === "Copter"
? apmParamDefsCopter
: apmParamDefsPlane
}, [aircraftTypeString])

const rcSelectOptions = useMemo(() => {
const rcOptions = paramDefs.RC1_OPTION?.Values
if (!rcOptions) return []

return Object.entries(rcOptions)
.sort((a, b) => {
// Always put "0" first
if (a[0] === "0") return -1
if (b[0] === "0") return 1
// Then sort by label alphabetically
return a[1].localeCompare(b[1])
})
.map(([value, label]) => ({
value: value,
label: label,
}))
}, [paramDefs])

function handleRcOptionChange(channel, newOption) {
dispatch(
emitSetRcConfigParam({
param_id: `RC${channel}_OPTION`,
value: parseInt(newOption),
}),
)
}

function handleReversedChange(channel, isReversed) {
dispatch(
emitSetRcConfigParam({
param_id: `RC${channel}_REVERSED`,
value: isReversed ? 1 : 0,
}),
)
}

useEffect(() => {
Expand All @@ -73,32 +107,60 @@ export default function RadioCalibration() {
}, [connected])

return (
<div className="m-4 flex flex-row gap-4 relative">
<table className="table-auto">
<tbody>
{Object.keys(channels).map((channel) => (
<tr key={channel}>
<td className="w-fit pb-2 pr-4">
<span className="font-bold">{channel} </span>
{channelsConfig[channel]?.map ??
getReadableRcOption(channelsConfig[channel]?.option)}
</td>
<td>
<Progress.Root className="w-[48rem] !h-6">
<div className="m-4">
<Table withRowBorders={false} className="!w-fit">
<Table.Thead>
<Table.Tr>
<Table.Th className="">Channel</Table.Th>
<Table.Th className="">Function/Option</Table.Th>
<Table.Th className="">Reversed</Table.Th>
<Table.Th className="w-[40rem]">PWM Value</Table.Th>
</Table.Tr>
</Table.Thead>
<Table.Tbody>
{Object.keys(pwmChannels).map((channel) => (
<Table.Tr key={channel} className="h-12">
<Table.Td>
<span className="font-bold text-lg">RC{channel}</span>
</Table.Td>
<Table.Td>
{channelsConfig[channel]?.map ? (
<span>{channelsConfig[channel].map}</span>
) : (
<Select
data={rcSelectOptions}
value={channelsConfig[channel]?.option?.toString() || "0"}
onChange={(value) => handleRcOptionChange(channel, value)}
placeholder="Select option"
allowDeselect={false}
searchable
/>
)}
</Table.Td>
<Table.Td>
<Checkbox
checked={channelsConfig[channel]?.reversed || false}
onChange={(event) =>
handleReversedChange(channel, event.currentTarget.checked)
}
/>
</Table.Td>
<Table.Td>
<Progress.Root className="!h-6">
<Progress.Section
value={getPercentageValueFromPWM(channels[channel])}
color={colors[(channel - 1) % colors.length]}
value={getPercentageValueFromPWM(pwmChannels[channel])}
color={COLOURS[(channel - 1) % COLOURS.length]}
>
<Progress.Label className="!text-lg !font-normal">
{channels[channel]}
{pwmChannels[channel]}
</Progress.Label>
</Progress.Section>
</Progress.Root>
</td>
</tr>
</Table.Td>
</Table.Tr>
))}
</tbody>
</table>
</Table.Tbody>
</Table>
</div>
)
}
10 changes: 10 additions & 0 deletions gcs/src/redux/middleware/emitters.js
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ import {
emitSetFlightMode,
emitSetGripper,
emitSetGripperConfigParam,
emitSetRcConfigParam,
emitTestAllMotors,
emitTestMotorSequence,
emitTestOneMotor,
Expand Down Expand Up @@ -297,6 +298,15 @@ export function handleEmitters(socket, store, action) {
emitter: emitGetRcConfig,
callback: () => socket.socket.emit("get_rc_config"),
},
{
emitter: emitSetRcConfigParam,
callback: () => {
socket.socket.emit("set_rc_config_param", {
param_id: action.payload.param_id,
value: action.payload.value,
})
},
},
]

for (const { emitter, callback } of emitHandlers) {
Expand Down
23 changes: 21 additions & 2 deletions gcs/src/redux/middleware/socketMiddleware.js
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,11 @@ import {
setGetGripperEnabled,
setGripperConfig,
setNumberOfMotors,
setRadioChannels,
setRadioPwmChannels,
setRefreshingFlightModeData,
setRefreshingGripperConfigData,
setShowMotorTestWarningModal,
updateChannelsConfigParam,
updateGripperConfigParam,
} from "../slices/configSlice.js"
import {
Expand Down Expand Up @@ -150,6 +151,7 @@ const ConfigSpecificSocketEvents = Object.freeze({
onSetFlightModeResult: "set_flight_mode_result",
onFrameTypeConfig: "frame_type_config",
onRcConfig: "rc_config",
onSetRcConfigResult: "set_rc_config_result",
})

const socketMiddleware = (store) => {
Expand All @@ -162,7 +164,7 @@ const socketMiddleware = (store) => {
chans[i] = msg[`chan${i}_raw`]
}

store.dispatch(setRadioChannels(chans))
store.dispatch(setRadioPwmChannels(chans))
}

const incomingMessageHandler = (msg) => {
Expand Down Expand Up @@ -809,6 +811,23 @@ const socketMiddleware = (store) => {
store.dispatch(setChannelsConfig(config))
})

socket.socket.on(
ConfigSpecificSocketEvents.onSetRcConfigResult,
(msg) => {
if (msg.success) {
showSuccessNotification(msg.message)
store.dispatch(
updateChannelsConfigParam({
param_id: msg.param_id,
value: msg.value,
}),
)
} else {
showErrorNotification(msg.message)
}
},
)

/*
Generic Drone Data
*/
Expand Down
41 changes: 34 additions & 7 deletions gcs/src/redux/slices/configSlice.js
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ const configSlice = createSlice({
frameClass: null,
numberOfMotors: 4,
showMotorTestWarningModal: true,
radioChannels: {
radioPwmChannels: {
1: 0,
2: 0,
3: 0,
Expand Down Expand Up @@ -101,14 +101,38 @@ const configSlice = createSlice({
if (action.payload === state.showMotorTestWarningModal) return
state.showMotorTestWarningModal = action.payload
},
setRadioChannels: (state, action) => {
if (action.payload === state.radioChannels) return
state.radioChannels = action.payload
setRadioPwmChannels: (state, action) => {
if (action.payload === state.radioPwmChannels) return
state.radioPwmChannels = action.payload
},
setChannelsConfig: (state, action) => {
if (action.payload === state.radioChannelsConfig) return
state.radioChannelsConfig = action.payload
},
updateChannelsConfigParam: (state, action) => {
const { param_id, value } = action.payload
// param_id is like "RC1_OPTION", "RC2_REVERSED", etc. so we need to separate out the channel number
const match = param_id.match(/^RC(\d+)_/)[1]
if (!match) return

const channelNum = match[1]

if (!state.radioChannelsConfig[channelNum]) return

// Get if its an option or reversed parameter
const isOption = param_id.endsWith("_OPTION")
const isReversed = param_id.endsWith("_REVERSED")
if (!isOption && !isReversed) return

if (isOption) {
// For option, value should be an integer
if (state.radioChannelsConfig[channelNum].option === value) return
state.radioChannelsConfig[channelNum].option = value
} else if (isReversed) {
if (state.radioChannelsConfig[channelNum].reversed === value) return
state.radioChannelsConfig[channelNum].reversed = value
}
},

// Emits
emitGetGripperEnabled: () => {},
Expand All @@ -123,6 +147,7 @@ const configSlice = createSlice({
emitTestMotorSequence: () => {},
emitTestAllMotors: () => {},
emitGetRcConfig: () => {},
emitSetRcConfigParam: () => {},
},
selectors: {
selectGetGripperEnabled: (state) => state.getGripperEnabled,
Expand All @@ -139,7 +164,7 @@ const configSlice = createSlice({
selectFrameClass: (state) => state.frameClass,
selectNumberOfMotors: (state) => state.numberOfMotors,
selectShowMotorTestWarningModal: (state) => state.showMotorTestWarningModal,
selectRadioChannels: (state) => state.radioChannels,
selectRadioPwmChannels: (state) => state.radioPwmChannels,
selectRadioChannelsConfig: (state) => state.radioChannelsConfig,
},
})
Expand All @@ -159,8 +184,9 @@ export const {
setFrameClass,
setNumberOfMotors,
setShowMotorTestWarningModal,
setRadioChannels,
setRadioPwmChannels,
setChannelsConfig,
updateChannelsConfigParam,

// Emitters
emitGetGripperEnabled,
Expand All @@ -175,6 +201,7 @@ export const {
emitTestMotorSequence,
emitTestAllMotors,
emitGetRcConfig,
emitSetRcConfigParam,
} = configSlice.actions

export const {
Expand All @@ -191,7 +218,7 @@ export const {
selectFrameClass,
selectNumberOfMotors,
selectShowMotorTestWarningModal,
selectRadioChannels,
selectRadioPwmChannels,
selectRadioChannelsConfig,
} = configSlice.selectors

Expand Down
4 changes: 2 additions & 2 deletions radio/app/controllers/gripperController.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from typing import TYPE_CHECKING

import serial
from app.customTypes import Response
from app.customTypes import Number, Response
from app.utils import commandAccepted
from pymavlink import mavutil

Expand Down Expand Up @@ -158,7 +158,7 @@ def getConfig(self) -> dict:

return config

def setGripperParam(self, param_id: str, value: float) -> bool:
def setGripperParam(self, param_id: str, value: Number) -> bool:
"""
Sets a gripper related parameter on the drone.
"""
Expand Down
Loading
Loading