@@ -17,10 +17,11 @@ import MissionItemsTable from "./components/missions/missionItemsTable"
1717import MissionsMapSection from "./components/missions/missionsMap"
1818import RallyItemsTable from "./components/missions/rallyItemsTable"
1919import NoDroneConnected from "./components/noDroneConnected"
20- import { intToCoord } from "./helpers/dataFormatters"
20+ import { coordToInt , intToCoord } from "./helpers/dataFormatters"
2121import {
2222 COPTER_MODES_FLIGHT_MODE_MAP ,
2323 MAV_AUTOPILOT_INVALID ,
24+ MAV_FRAME_LIST ,
2425 PLANE_MODES_FLIGHT_MODE_MAP ,
2526} from "./helpers/mavlinkConstants"
2627import {
@@ -60,6 +61,12 @@ export default function Missions() {
6061 key : "homePosition" ,
6162 defaultValue : null ,
6263 } )
64+ const [ targetInfo , setTargetInfo ] = useSessionStorage ( {
65+ key : "targetInfo" ,
66+ defaultValue : { target_component : 0 , target_system : 255 } ,
67+ } )
68+
69+ const newMissionItemAltitude = 30 // TODO: Make this configurable
6370
6471 // Heartbeat data
6572 const [ heartbeatData , setHeartbeatData ] = useState ( { system_status : 0 } )
@@ -92,6 +99,7 @@ export default function Missions() {
9299 } else {
93100 socket . emit ( "set_state" , { state : "missions" } )
94101 socket . emit ( "get_home_position" )
102+ socket . emit ( "get_target_info" )
95103 }
96104
97105 socket . on ( "incoming_msg" , ( msg ) => {
@@ -108,14 +116,18 @@ export default function Missions() {
108116 }
109117 } )
110118
119+ socket . on ( "target_info" , ( data ) => {
120+ if ( data ) {
121+ setTargetInfo ( data )
122+ }
123+ } )
124+
111125 socket . on ( "current_mission" , ( data ) => {
112126 if ( ! data . success ) {
113127 showErrorNotification ( data . message )
114128 return
115129 }
116130
117- console . log ( data )
118-
119131 if ( data . mission_type === "mission" ) {
120132 const missionItemsWithIds = [ ]
121133 for ( let missionItem of data . items ) {
@@ -146,6 +158,7 @@ export default function Missions() {
146158 return ( ) => {
147159 socket . off ( "incoming_msg" )
148160 socket . off ( "home_position_result" )
161+ socket . off ( "target_info" )
149162 socket . off ( "current_mission" )
150163 socket . off ( "write_mission_result" )
151164 }
@@ -168,6 +181,34 @@ export default function Missions() {
168181 return missionItem
169182 }
170183
184+ function addNewMissionItem ( lat , lon ) {
185+ const newMissionItem = {
186+ id : uuidv4 ( ) ,
187+ seq : missionItems . length ,
188+ x : coordToInt ( lat ) ,
189+ y : coordToInt ( lon ) ,
190+ z : newMissionItemAltitude ,
191+ frame : parseInt (
192+ Object . keys ( MAV_FRAME_LIST ) . find (
193+ ( key ) => MAV_FRAME_LIST [ key ] === "MAV_FRAME_GLOBAL_RELATIVE_ALT" ,
194+ ) ,
195+ ) ,
196+ command : 16 , // MAV_CMD_NAV_WAYPOINT
197+ param1 : 0 ,
198+ param2 : 0 ,
199+ param3 : 0 ,
200+ param4 : 0 ,
201+ current : 0 ,
202+ autocontinue : 1 ,
203+ target_component : targetInfo . target_component ,
204+ target_system : targetInfo . target_system ,
205+ mission_type : 0 ,
206+ mavpackettype : "MISSION_ITEM_INT" ,
207+ }
208+
209+ setMissionItems ( ( prevItems ) => [ ...prevItems , newMissionItem ] )
210+ }
211+
171212 function updateMissionItem ( updatedMissionItem ) {
172213 setMissionItems ( ( prevItems ) =>
173214 prevItems . map ( ( item ) =>
@@ -187,6 +228,51 @@ export default function Missions() {
187228 )
188229 }
189230
231+ function deleteMissionItem ( missionItemId ) {
232+ setMissionItems ( ( prevItems ) => {
233+ const updatedItems = prevItems . filter ( ( item ) => item . id !== missionItemId )
234+
235+ return updatedItems . map ( ( item , index ) => ( {
236+ ...item ,
237+ seq : index , // Reassign seq based on the new order
238+ } ) )
239+ } )
240+ }
241+
242+ function updateMissionItemOrder ( missionItemId , indexIncrement ) {
243+ setMissionItems ( ( prevItems ) => {
244+ const currentIndex = prevItems . findIndex (
245+ ( item ) => item . id === missionItemId ,
246+ )
247+
248+ // Ensure the item exists and the swap is within bounds
249+ if (
250+ currentIndex === - 1 ||
251+ ( indexIncrement === - 1 && currentIndex === 0 ) ||
252+ ( indexIncrement === 1 && currentIndex === prevItems . length - 1 )
253+ ) {
254+ return prevItems // No changes if out of bounds
255+ }
256+
257+ // Calculate the new index
258+ const newIndex = currentIndex + indexIncrement
259+
260+ // Create a copy of the items array
261+ const updatedItems = [ ...prevItems ]
262+
263+ // Swap the items
264+ const temp = updatedItems [ currentIndex ]
265+ updatedItems [ currentIndex ] = updatedItems [ newIndex ]
266+ updatedItems [ newIndex ] = temp
267+
268+ // Update the seq values
269+ updatedItems [ currentIndex ] . seq = currentIndex
270+ updatedItems [ newIndex ] . seq = newIndex
271+
272+ return updatedItems
273+ } )
274+ }
275+
190276 function readMissionFromDrone ( ) {
191277 socket . emit ( "get_current_mission" , { type : activeTab } )
192278 }
@@ -317,6 +403,7 @@ export default function Missions() {
317403 currentTab = { activeTab }
318404 markerDragEndCallback = { updateMissionItem }
319405 rallyDragEndCallback = { updateRallyItem }
406+ addNewMissionItem = { addNewMissionItem }
320407 mapId = "missions"
321408 />
322409 </ div >
@@ -350,6 +437,8 @@ export default function Missions() {
350437 missionItems = { missionItems }
351438 aircraftType = { aircraftType }
352439 updateMissionItem = { updateMissionItem }
440+ deleteMissionItem = { deleteMissionItem }
441+ updateMissionItemOrder = { updateMissionItemOrder }
353442 />
354443 </ Tabs . Panel >
355444 < Tabs . Panel value = "fence" > </ Tabs . Panel >
0 commit comments