@@ -26,6 +26,7 @@ def __init__(self, drone: Drone) -> None:
2626 self .seq : int = 0
2727 self .session : int = 0
2828 self .last_op : Optional [mavftp_op .FTP_OP ] = None
29+ self .current_op : Optional [str ] = None
2930
3031 # Directory listing state
3132 self .dir_offset : int = 0
@@ -413,46 +414,58 @@ def listFiles(self, path: str) -> Response:
413414 Returns:
414415 Response: A response object containing the status and data or error message.
415416 """
416- if path == "" :
417+ # Check if another operation is in progress
418+ if self .current_op is not None :
417419 return {
418420 "success" : False ,
419- "message" : "Path cannot be empty " ,
421+ "message" : f"FTP operation already in progress: { self . current_op } " ,
420422 }
421423
422- encoded_path = bytearray (path , "ascii" )
423- directory_offset = 0
424- op = mavftp_op .FTP_OP (
425- self .seq ,
426- self .session ,
427- mavftp_op .OP_ListDirectory ,
428- len (encoded_path ),
429- 0 ,
430- 0 ,
431- directory_offset ,
432- encoded_path ,
433- )
424+ try :
425+ self .current_op = "list_files"
434426
435- self .dir_offset = 0
436- self .list_result = []
437- self .list_temp_result = []
427+ if path == "" :
428+ return {
429+ "success" : False ,
430+ "message" : "Path cannot be empty" ,
431+ }
438432
439- self .drone .logger .info (f"Listing files in directory: { path } " )
433+ encoded_path = bytearray (path , "ascii" )
434+ directory_offset = 0
435+ op = mavftp_op .FTP_OP (
436+ self .seq ,
437+ self .session ,
438+ mavftp_op .OP_ListDirectory ,
439+ len (encoded_path ),
440+ 0 ,
441+ 0 ,
442+ directory_offset ,
443+ encoded_path ,
444+ )
440445
441- self ._sendFtpCommand (op )
442- response = self ._processFtpResponse ("list_files" )
446+ self .dir_offset = 0
447+ self .list_result = []
448+ self .list_temp_result = []
443449
444- if response .get ("success" , False ) is False :
445- return response
450+ self .drone .logger .info (f"Listing files in directory: { path } " )
446451
447- self .drone .logger .info (
448- f"Successfully listed { len (self .list_result )} files in directory: { path } "
449- )
452+ self ._sendFtpCommand (op )
453+ response = self ._processFtpResponse ("list_files" )
454+
455+ if response .get ("success" , False ) is False :
456+ return response
450457
451- return {
452- "success" : True ,
453- "message" : "Directory listing retrieved successfully" ,
454- "data" : self ._convertDirectoryEntriesToDicts (self .list_result , path ),
455- }
458+ self .drone .logger .info (
459+ f"Successfully listed { len (self .list_result )} files in directory: { path } "
460+ )
461+
462+ return {
463+ "success" : True ,
464+ "message" : "Directory listing retrieved successfully" ,
465+ "data" : self ._convertDirectoryEntriesToDicts (self .list_result , path ),
466+ }
467+ finally :
468+ self .current_op = None
456469
457470 def readFile (
458471 self , path : str , size : Optional [int ] = None , offset : int = 0
@@ -468,69 +481,81 @@ def readFile(
468481 Returns:
469482 Response: A response object containing the file data or error message.
470483 """
471- if not path :
484+ # Check if another operation is in progress
485+ if self .current_op is not None :
472486 return {
473487 "success" : False ,
474- "message" : "File path cannot be empty " ,
488+ "message" : f"FTP operation already in progress: { self . current_op } " ,
475489 }
476490
477- # Reset read state
478- self .read_buffer = BytesIO ()
479- self .read_total = 0
480- self .read_gaps = []
481- self .reached_eof = False
482- self .requested_offset = offset
483- self .requested_size = (
484- size if size is not None else 0
485- ) # 0 means read entire file
486- self .remote_file_size = None
487- self .last_burst_read = None
488-
489- # Send OpenFileRO command
490- encoded_path = bytearray (path , "ascii" )
491- op = mavftp_op .FTP_OP (
492- self .seq ,
493- self .session ,
494- mavftp_op .OP_OpenFileRO ,
495- len (encoded_path ),
496- 0 ,
497- 0 ,
498- 0 ,
499- encoded_path ,
500- )
491+ try :
492+ self .current_op = "read_file"
501493
502- self .drone .logger .info (
503- f"Reading file: { path } (offset={ offset } , size={ size if size else 'entire file' } )"
504- )
494+ if not path :
495+ return {
496+ "success" : False ,
497+ "message" : "File path cannot be empty" ,
498+ }
505499
506- self ._sendFtpCommand (op )
507- response = self ._processFtpResponse ("read_file" , timeout = 30 )
500+ # Reset read state
501+ self .read_buffer = BytesIO ()
502+ self .read_total = 0
503+ self .read_gaps = []
504+ self .reached_eof = False
505+ self .requested_offset = offset
506+ self .requested_size = (
507+ size if size is not None else 0
508+ ) # 0 means read entire file
509+ self .remote_file_size = None
510+ self .last_burst_read = None
511+
512+ # Send OpenFileRO command
513+ encoded_path = bytearray (path , "ascii" )
514+ op = mavftp_op .FTP_OP (
515+ self .seq ,
516+ self .session ,
517+ mavftp_op .OP_OpenFileRO ,
518+ len (encoded_path ),
519+ 0 ,
520+ 0 ,
521+ 0 ,
522+ encoded_path ,
523+ )
508524
509- if response .get ("success" , False ) is False :
510- return response
525+ self .drone .logger .info (
526+ f"Reading file: { path } (offset={ offset } , size={ size if size else 'entire file' } )"
527+ )
511528
512- # Extract the requested portion of the data
513- self .read_buffer .seek (0 )
514- all_data = self .read_buffer .read ()
529+ self ._sendFtpCommand (op )
530+ response = self ._processFtpResponse ("read_file" , timeout = 30 )
515531
516- if self .requested_size > 0 :
517- # Return only the requested size from the requested offset
518- result_data = all_data [
519- self .requested_offset : self .requested_offset + self .requested_size
520- ]
521- else :
522- # Return entire file
523- result_data = all_data
532+ if response .get ("success" , False ) is False :
533+ return response
524534
525- self . drone . logger . info (
526- f"Successfully read { len ( result_data ) } bytes from file: { path } "
527- )
535+ # Extract the requested portion of the data
536+ self . read_buffer . seek ( 0 )
537+ all_data = self . read_buffer . read ( )
528538
529- return {
530- "success" : True ,
531- "message" : "File read successfully" ,
532- "data" : {"file_data" : result_data , "file_name" : path .split ("/" )[- 1 ]},
533- }
539+ if self .requested_size > 0 :
540+ # Return only the requested size from the requested offset
541+ result_data = all_data [
542+ self .requested_offset : self .requested_offset + self .requested_size
543+ ]
544+ else :
545+ # Return entire file
546+ result_data = all_data
547+
548+ self .drone .logger .info (
549+ f"Successfully read { len (result_data )} bytes from file: { path } "
550+ )
551+
552+ return {
553+ "success" : True ,
554+ "message" : "File read successfully" ,
555+ "data" : {"file_data" : result_data , "file_name" : path .split ("/" )[- 1 ]},
556+ }
557+ finally :
558+ self .current_op = None
534559
535560 def _handleOpenFileReadOnlyResponse (self , response_op : mavftp_op .FTP_OP ) -> bool :
536561 """
0 commit comments