From 8c2f7661b762fb378415e2df4b2634910acd3eb4 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 13 Jul 2013 13:19:15 -0600 Subject: More Zmodem bugfixes and new files --- apps/include/zmodem.h | 59 +- apps/system/zmodem/Kconfig | 16 +- apps/system/zmodem/Makefile | 6 +- apps/system/zmodem/README.txt | 41 + apps/system/zmodem/sz_main.c | 45 +- apps/system/zmodem/zm.h | 16 +- apps/system/zmodem/zm_proto.c | 5 +- apps/system/zmodem/zm_send.c | 1684 +++++++++++++++++++++++++++++++++++++++++ apps/system/zmodem/zm_state.c | 960 +++++++++++++++++++++++ 9 files changed, 2806 insertions(+), 26 deletions(-) create mode 100755 apps/system/zmodem/README.txt create mode 100644 apps/system/zmodem/zm_send.c create mode 100644 apps/system/zmodem/zm_state.c (limited to 'apps') diff --git a/apps/include/zmodem.h b/apps/include/zmodem.h index 5ba938254..101512f97 100644 --- a/apps/include/zmodem.h +++ b/apps/include/zmodem.h @@ -53,6 +53,15 @@ * Pre-processor Definitions ****************************************************************************/ /* Configuration ************************************************************/ + +/* The default device used by the Zmodem commands if the -d option is not + * provided on the sz or rz command line. + */ + +#ifndef CONFIG_SYSTEM_ZMODEM_DEVNAME +# define CONFIG_SYSTEM_ZMODEM_DEVNAME "/dev/console" +#endif + /* The size of one buffer used to read data from the remote peer */ #ifndef CONFIG_SYSTEM_ZMODEM_RCVBUFSIZE @@ -165,16 +174,41 @@ extern "C" * remfd - The R/W file/socket descriptor to use for communication with the * remote peer. * + * Returned Value: + * An opaque handle that can be use with zmr_receive() and zmr_release(). + * ****************************************************************************/ ZMRHANDLE zmr_initialize(int remfd); +/**************************************************************************** + * Name: zmr_receive + * + * Description: + * Receive file(s) sent from the remote peer. + * + * Input Parameters: + * handle - The handler created by zmr_initialize(). + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +int zmr_receive(ZMRHANDLE handle); + /**************************************************************************** * Name: zmr_release * * Description: * Called by the user when there are no more files to receive. * + * Input Parameters: + * handle - The handler created by zmr_initialize(). + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * ****************************************************************************/ int zmr_release(ZMRHANDLE); @@ -198,6 +232,9 @@ int zmr_release(ZMRHANDLE); * remfd - The R/W file/socket descriptor to use for communication with the * remote peer. * + * Returned Value: + * An opaque handle that can be use with zmx_send() and zms_release() + * ****************************************************************************/ ZMSHANDLE zms_initialize(int remfd); @@ -209,12 +246,15 @@ ZMSHANDLE zms_initialize(int remfd); * Send a file. * * Input Parameters: - * handle - Handle previoulsy returned by xms_initialize() - * filename - The name of the local file to transfer + * handle - Handle previoulsy returned by xms_initialize() + * filename - The name of the local file to transfer * rfilename - The name of the remote file name to create - * option - Describes optional transfer behavior - * f1 - The F1 transfer flags - * skip - True: Skip if file not present at receiving end. + * option - Describes optional transfer behavior + * f1 - The F1 transfer flags + * skip - True: Skip if file not present at receiving end. + * + * Returned Value: + * Zero on success; a negated errno value on failure. * ****************************************************************************/ @@ -228,6 +268,12 @@ int zms_send(ZMSHANDLE handle, FAR const char *filename, * Description: * Called by the user when there are no more files to send. * + * Input Parameters: + * handle - The handler created by zms_initialize(). + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * ****************************************************************************/ int zms_release(ZMSHANDLE handle); @@ -240,6 +286,9 @@ int zms_release(ZMSHANDLE handle); * must provide the following interface in order to enable/disable hardware * flow control on the device used to communicate with the remote peer. * + * Returned Value: + * Zero on success; a negated errno value on failure. + * ****************************************************************************/ #ifdef CONFIG_SYSTEM_ZMODEM_FULLSTREAMING diff --git a/apps/system/zmodem/Kconfig b/apps/system/zmodem/Kconfig index 167146e97..64ab3a92e 100644 --- a/apps/system/zmodem/Kconfig +++ b/apps/system/zmodem/Kconfig @@ -11,6 +11,13 @@ config SYSTEM_ZMODEM if SYSTEM_ZMODEM +config SYSTEM_ZMODEM_DEVNAME + string "Default Zmodem device" + default "/dev/console" + ---help-- + The default device used by the Zmodem commands if the -d option is + not provided on the sz or rz command line. Default: "/dev/console". + config SYSTEM_ZMODEM_RCVBUFSIZE int "Receive buffer size" default 512 @@ -36,9 +43,12 @@ config SYSTEM_ZMODEM_MOUNTPOINT string "Zmodem sandbox" default "/tmp" ---help--- - Absolute pathes are not accepted. This configuration value must be - set to provide the path to the file storage directory (such as a - mountpoint directory). + Absolute pathes in received file names are not accepted. This + configuration value must be set to provide the path to the file + storage directory (such as a mountpoint directory). + + Names of file send by the sz commond, on the other hand, must be + absolute paths beginning with '/'. config SYSTEM_ZMODEM_SENDSAMPLE bool "Reverse channel" diff --git a/apps/system/zmodem/Makefile b/apps/system/zmodem/Makefile index 7f2bc2277..571e0d2de 100644 --- a/apps/system/zmodem/Makefile +++ b/apps/system/zmodem/Makefile @@ -44,13 +44,13 @@ endif # Zmodem sz and rz commands PRIORITY = SCHED_PRIORITY_DEFAULT -STACKSIZE = 768 +STACKSIZE = 1536 ASRCS = -CSRCS = sz_main.c +CSRCS = sz_main.c zm_send.c CSRCS += rz_main.c -CSRCS += zm_proto.c zm_watchdog.c zm_utils.c zm_dumpbuffer.c +CSRCS += zm_state.c zm_proto.c zm_watchdog.c zm_utils.c zm_dumpbuffer.c AOBJS = $(ASRCS:.S=$(OBJEXT)) COBJS = $(CSRCS:.c=$(OBJEXT)) diff --git a/apps/system/zmodem/README.txt b/apps/system/zmodem/README.txt new file mode 100755 index 000000000..63d15cecb --- /dev/null +++ b/apps/system/zmodem/README.txt @@ -0,0 +1,41 @@ +README +====== + +Using NuttX Zmodem with a Linux Host +==================================== + + The NuttX Zmodem commands have been verified against the rzsz programs + running on a Linux PC. To send a file to the PC, first make sure that + the serial port is configured to work with the board: + + $ sudo stty -F /dev/ttyS0 57600 + $ sudo stty -F /dev/ttyS0 + + start rz on the Linux host: + + $ sudo rz /dev/ttyS0 + + You can add the rz -v option multiple times, each increases the level + of debug output. If you want to capture the Linux rz output, then + re-direct stderr to a log file by adding 2>rz.log to the end of the + rz command. + + NOTE: The NuttX Zmodem does sends rz\n when it starts in compliance with + the Zmodem specification. On Linux this, however, seems to start some + other, incompatible version of rz. You need to start rz manually to + make sure that the correct version is selected. You can tell when this + evil rz/sz has inserted itself because you will see the '^' (0x5e) + character replacing the standard Zmodem ZDLE character (0x19) in the + binary data stream. + + If you don't have the rz command on your Linux box, the package to + install rzsz (or possibily lrzsz). + + Then on the target: + + > sz -d /dev/ttyS1 + + Where filename is the full path to the file to send (i.e., it begins + with the '/' character). + + \ No newline at end of file diff --git a/apps/system/zmodem/sz_main.c b/apps/system/zmodem/sz_main.c index c6693f0b5..e20af9e97 100644 --- a/apps/system/zmodem/sz_main.c +++ b/apps/system/zmodem/sz_main.c @@ -42,8 +42,10 @@ #include #include #include +#include #include #include +#include #include #include @@ -55,11 +57,13 @@ static void show_usage(FAR const char *progname, int errcode) { - fprintf(stderr, "USAGE: %s [OPTIONS] [ [ ...]]\n", progname); + fprintf(stderr, "USAGE: %s [OPTIONS] [ [ ...]]\n", + progname); fprintf(stderr, "\nWhere:\n"); fprintf(stderr, "\t is the local file name\n"); fprintf(stderr, "\nand OPTIONS include the following:\n"); - fprintf(stderr, "\t-d : Communication device to use. Default /dev/console\n"); + fprintf(stderr, "\t-d : Communication device to use. Default: %s\n", + CONFIG_SYSTEM_ZMODEM_DEVNAME); fprintf(stderr, "\t-r : Remote file name. Default \n"); fprintf(stderr, "\t-x : Transfer type\n"); fprintf(stderr, "\t\t0: Normal file (default)\n"); @@ -91,7 +95,7 @@ int sz_main(int argc, FAR char **argv) enum zm_option_e xfroption = XM_OPTION_REPLACE; ZMSHANDLE handle; FAR const char *rname = NULL; - FAR const char *devname = "/dev/console"; + FAR const char *devname = CONFIG_SYSTEM_ZMODEM_DEVNAME; FAR char *endptr; bool skip = false; long tmp; @@ -197,11 +201,44 @@ int sz_main(int argc, FAR char **argv) */ FAR const char *nextlname = argv[optind]; - FAR const char *nextrname = rname ? rname : nextlname; + FAR const char *nextrname; + FAR char *ralloc; + + /* Get the next remote file name */ + + nextrname = rname; + ralloc = NULL; + + if (!nextrname) + { + /* No remote filename, use the basename of the local filename. + * NOTE: that we have to duplicate the local filename to do this + * because basename() modifies the original string. + */ + + ralloc = strdup(nextlname); + if (!ralloc) + { + fprintf(stderr, "ERROR: Out-of-memory\n"); + goto errout_with_device; + } + + nextrname = basename(ralloc); + } /* Transfer the file */ ret = zms_send(handle, nextlname, nextrname, xfrtype, xfroption, skip); + + /* Free any allocations made for the remote file name */ + + if (ralloc) + { + free(ralloc); + } + + /* Check if the transfer was successful */ + if (ret < 0) { fprintf(stderr, "ERROR: Transfer of %s failed: %d\n", diff --git a/apps/system/zmodem/zm.h b/apps/system/zmodem/zm.h index e0caf8837..bb849d21d 100644 --- a/apps/system/zmodem/zm.h +++ b/apps/system/zmodem/zm.h @@ -200,7 +200,7 @@ #define ZM_FLAG_APPEND (1 << 8) /* Append to the existing file */ #define ZM_FLAG_TIMEOUT (1 << 9) /* A timeout has been detected */ -/* zm_parse() success/error return code definitions: +/* The Zmodem parser success/error return code definitions: * * < 0 : Transfer terminated due to an error * = 0 : Transfer still in progress @@ -694,19 +694,17 @@ int zm_sendbinhdr(FAR struct zm_state_s *pzm, int type, FAR const uint8_t *buffer); /**************************************************************************** - * Name: zm_parse + * Name: zm_datapump * * Description: - * New data from the remote peer is available in pzm->rcvbuf. The number - * number of bytes of new data is given by rcvlen. - * - * This function will parse the data in the buffer and, based on the - * current state and the contents of the buffer, will drive the Zmodem - * state machine. + * Drive the Zmodem state machine by reading data from the remote peer and + * providing that data to the parser. This loop runs until a fatal error + * is detected or until the state machine reports that the transfer has + * completed successfully. * ****************************************************************************/ -int zm_parse(FAR struct zm_state_s *pzm, size_t rcvlen); +int zm_datapump(FAR struct zm_state_s *pzm); /**************************************************************************** * Name: zm_readstate diff --git a/apps/system/zmodem/zm_proto.c b/apps/system/zmodem/zm_proto.c index 9af600f8a..f730a984c 100644 --- a/apps/system/zmodem/zm_proto.c +++ b/apps/system/zmodem/zm_proto.c @@ -199,7 +199,8 @@ int zm_senddata(FAR struct zm_state_s *pzm, FAR const uint8_t *buffer, } term = ZCRCW; - zmdbg("zbin=%c, buflen=%d, term=%c\n", zbin, buflen, term); + zmdbg("zbin=%c, buflen=%d, term=%c flags=%04x\n", + zbin, buflen, term, pzm->flags); /* Transfer the data to the I/O buffer, accumulating the CRC */ @@ -496,6 +497,6 @@ int zm_sendbinhdr(FAR struct zm_state_s *pzm, int type, } else { - return zm_sendbin16hdr(pzm, type, buffer); + return zm_sendbin32hdr(pzm, type, buffer); } } diff --git a/apps/system/zmodem/zm_send.c b/apps/system/zmodem/zm_send.c new file mode 100644 index 000000000..5982834da --- /dev/null +++ b/apps/system/zmodem/zm_send.c @@ -0,0 +1,1684 @@ +/**************************************************************************** + * system/zmodem/zm_send.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "The ZMODEM Inter Application File Transfer Protocol", Chuck Forsberg, + * Omen Technology Inc., October 14, 1988 + * + * This is an original work, but I want to make sure that credit is given + * where due: Parts of the state machine design were inspired by the + * Zmodem library of Edward A. Falk, dated January, 1995. License + * unspecified. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "zm.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Zmodem transmit states. + * + * A simple transaction, one file, no errors, no CHALLENGE, overlapped I/O. + * These happen when zm_initialize() is called: + * + * Sender Receiver State + * -------------- ------------ -------- + * "rz\r" ----> N/A + * ZRQINIT ----> ZMS_START + * <---- ZRINIT + * ZSINIT ----> ZMS_INITACK + * <---- ZACK End-of-Transfer + * + * These happen each time that zm_send() is called: + * + * Sender Receiver State + * -------------- ------------ -------- + * ZFILE ----> ZMS_FILEWAIT + * <---- ZRPOS + * ZCRC ----> ZMS_CRCWAIT + * <---- ZRPOS + * ZDATA ----> ZMS_SENDING + * Data packets ----> [Perhaps ZMS_SENDWAIT<->ZMS_SENDING] + * Last packet ----> ZMS_SENDDONE + * ZEOF ----> ZMS_SENDEOF + * <---- ZRINIT + * ZFIN ----> ZMS_FINISH + * <---- ZFIN End-of-Transfer + * + * And, finally, when zm_release() is called: + * + * Sender Receiver State + * -------------- ------------ -------- + * OO ----> + */ + +enum zmodem_state_e +{ + ZMS_START = 0, /* ZRQINIT sent, waiting for ZRINIT from receiver */ + ZMS_INITACK, /* Received ZRINIT, sent ZSINIT, waiting for ZACK */ + ZMS_FILEWAIT, /* Sent file header, waiting for ZRPOS */ + ZMS_CRCWAIT, /* Sent file CRC, waiting for ZRPOS */ + ZMS_SENDING, /* Sending data subpackets, ready for interrupt */ + ZMS_SENDWAIT, /* Waiting for ZACK */ + ZMS_SENDDONE, /* File finished, need to send ZEOF */ + ZMS_SENDEOF, /* Sent ZEOF, waiting for ZACK */ + ZMS_FINISH, /* Sent ZFIN, waiting for ZFIN */ + ZMS_COMMAND, /* Waiting for command data */ + ZMS_MESSAGE, /* Waiting for message from received */ + ZMS_DONE /* Finished with the file transfer */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ +/* Transition actions */ + +static int zms_rinit(FAR struct zm_state_s *pzm); +static int zms_attention(FAR struct zm_state_s *pzm); +static int zms_challenge(FAR struct zm_state_s *pzm); +static int zms_abort(FAR struct zm_state_s *pzm); +static int zms_ignore(FAR struct zm_state_s *pzm); +static int zms_command(FAR struct zm_state_s *pzm); +static int zms_message(FAR struct zm_state_s *pzm); +static int zms_stderrdata(FAR struct zm_state_s *pzm); +static int zms_initdone(FAR struct zm_state_s *pzm); +static int zms_sendzsinit(FAR struct zm_state_s *pzm); +static int zms_sendfilename(FAR struct zm_state_s *pzm); +static int zms_endoftransfer(FAR struct zm_state_s *pzm); +static int zms_fileskip(FAR struct zm_state_s *pzm); +static int zms_sendfiledata(FAR struct zm_state_s *pzm); +static int zms_sendpacket(FAR struct zm_state_s *pzm); +static int zms_filecrc(FAR struct zm_state_s *pzm); +static int zms_sendack(FAR struct zm_state_s *pzm); +static int zms_sendwaitack(FAR struct zm_state_s *pzm); +static int zms_sendnak(FAR struct zm_state_s *pzm); +static int zms_sendrpos(FAR struct zm_state_s *pzm); +static int zms_senddoneack(FAR struct zm_state_s *pzm); +static int zms_resendeof(FAR struct zm_state_s *pzm); +static int zms_xfrdone(FAR struct zm_state_s *pzm); +static int zms_finish(FAR struct zm_state_s *pzm); +static int zms_timeout(FAR struct zm_state_s *pzm); +static int zms_cmdto(FAR struct zm_state_s *pzm); +static int zms_doneto(FAR struct zm_state_s *pzm); +static int zms_error(FAR struct zm_state_s *pzm); + +/* Internal helpers */ + +static int zms_startfiledata(FAR struct zms_state_s *pzms); +static int zms_sendfile(FAR struct zms_state_s *pzms, FAR const char *filename, + FAR const char *rfilename, uint8_t f0, uint8_t f1); + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* Events handled in state ZMS_START - ZRQINIT sent, waiting for ZRINIT from + * receiver + */ + +static const struct zm_transition_s g_zms_start[] = +{ + {ZME_RINIT, true, ZMS_START, zms_rinit}, + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_CHALLENGE, true, ZMS_START, zms_challenge}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_NAK, false, ZMS_START, zms_ignore}, + {ZME_COMMAND, false, ZMS_COMMAND, zms_command}, + {ZME_STDERR, false, ZMS_MESSAGE, zms_message}, + {ZME_TIMEOUT, false, ZMS_START, zms_timeout}, + {ZME_ERROR, false, ZMS_START, zms_error}, +}; + +/* Events handled in state ZMS_INITACK - Received ZRINIT, sent (optional) + * ZSINIT, waiting for ZACK + */ + +static const struct zm_transition_s g_zms_init[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_ACK, true, ZMS_INITACK, zms_initdone}, + {ZME_NAK, true, ZMS_INITACK, zms_sendzsinit}, + {ZME_RINIT, true, ZMS_INITACK, zms_rinit}, + {ZME_CHALLENGE, true, ZMS_INITACK, zms_challenge}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_COMMAND, false, ZMS_COMMAND, zms_command}, + {ZME_STDERR, false, ZMS_MESSAGE, zms_message}, + {ZME_TIMEOUT, false, ZMS_INITACK, zms_timeout}, + {ZME_ERROR, false, ZMS_INITACK, zms_error}, +}; + +/* Events handled in state ZMS_FILEWAIT- Sent file header, waiting for ZRPOS */ + +static const struct zm_transition_s g_zms_filewait[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_RPOS, true, ZMS_SENDING, zms_sendfiledata}, + {ZME_SKIP, true, ZMS_FILEWAIT, zms_fileskip}, + {ZME_CRC, true, ZMS_FILEWAIT, zms_filecrc}, + {ZME_NAK, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_RINIT, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_CHALLENGE, true, ZMS_FILEWAIT, zms_challenge}, + {ZME_COMMAND, false, ZMS_COMMAND, zms_command}, + {ZME_STDERR, false, ZMS_MESSAGE, zms_message}, + {ZME_TIMEOUT, false, ZMS_FILEWAIT, zms_timeout}, + {ZME_ERROR, false, ZMS_FILEWAIT, zms_error}, +}; + +/* Events handled in state ZMS_CRCWAIT - Sent file CRC, waiting for ZRPOS + * response. + */ + +static const struct zm_transition_s g_zms_crcwait[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_RPOS, true, ZMS_SENDING, zms_sendfiledata}, + {ZME_SKIP, true, ZMS_FILEWAIT, zms_fileskip}, + {ZME_NAK, true, ZMS_CRCWAIT, zms_filecrc}, + {ZME_RINIT, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_CRC, false, ZMS_CRCWAIT, zms_filecrc}, + {ZME_CHALLENGE, false, ZMS_CRCWAIT, zms_challenge}, + {ZME_COMMAND, false, ZMS_COMMAND, zms_command}, + {ZME_STDERR, false, ZMS_MESSAGE, zms_message}, + {ZME_TIMEOUT, false, ZMS_CRCWAIT, zms_timeout}, + {ZME_ERROR, false, ZMS_CRCWAIT, zms_error}, +}; + +/* Events handled in state ZMS_SENDING - Sending data subpackets, ready for + * interrupt + */ + +static const struct zm_transition_s g_zms_sending[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_ACK, false, ZMS_SENDING, zms_sendack}, + {ZME_RPOS, true, ZMS_SENDING, zms_sendrpos}, + {ZME_SKIP, true, ZMS_FILEWAIT, zms_fileskip}, + {ZME_NAK, true, ZMS_SENDING, zms_sendnak}, + {ZME_RINIT, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_TIMEOUT, false, ZMS_SENDING, zms_sendpacket}, + {ZME_ERROR, false, ZMS_SENDING, zms_error}, +}; + +/* Events handled in state ZMS_SENDWAIT - Waiting for ZACK */ + +static const struct zm_transition_s g_zms_sendwait[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_ACK, false, ZMS_SENDING, zms_sendwaitack}, + {ZME_RPOS, false, ZMS_SENDWAIT, zms_sendrpos}, + {ZME_SKIP, true, ZMS_FILEWAIT, zms_fileskip}, + {ZME_NAK, false, ZMS_SENDING, zms_sendnak}, + {ZME_RINIT, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_TIMEOUT, false, ZMS_SENDWAIT, zms_timeout}, + {ZME_ERROR, false, ZMS_SENDWAIT, zms_error}, +}; + +/* Events handled in state ZMS_SENDDONE - File sent, need to send ZEOF */ + +static const struct zm_transition_s g_zms_senddone[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_ACK, false, ZMS_SENDWAIT, zms_senddoneack}, + {ZME_RPOS, true, ZMS_SENDING, zms_sendrpos}, + {ZME_SKIP, true, ZMS_FILEWAIT, zms_fileskip}, + {ZME_NAK, true, ZMS_SENDING, zms_sendnak}, + {ZME_RINIT, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_ERROR, false, ZMS_SENDWAIT, zms_error}, +}; + +/* Events handled in state ZMS_SENDEOF - Sent ZEOF, waiting for ZACK or + * ZRINIT + * + * Paragraph 8.2: "The sender sends a ZEOF header with the file ending + * offset equal to the number of characters in the file. The receiver + * compares this number with the number of characters received. If the + * receiver has received all of the file, it closes the file. If the + * file close was satisfactory, the receiver responds with ZRINIT. If + * the receiver has not received all the bytes of the file, the receiver + * ignores the ZEOF because a new ZDATA is coming. If the receiver cannot + * properly close the file, a ZFERR header is sent. + */ + +const struct zm_transition_s g_zms_sendeof[] = +{ + {ZME_RINIT, true, ZMS_START, zms_endoftransfer}, + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_ACK, false, ZMS_SENDEOF, zms_ignore}, + {ZME_RPOS, true, ZMS_SENDWAIT, zms_sendrpos}, + {ZME_SKIP, true, ZMS_START, zms_fileskip}, + {ZME_NAK, true, ZMS_SENDEOF, zms_resendeof}, + {ZME_RINIT, true, ZMS_FILEWAIT, zms_sendfilename}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_TIMEOUT, false, ZMS_SENDEOF, zms_timeout}, + {ZME_ERROR, false, ZMS_SENDEOF, zms_error}, +}; + +/* Events handled in state ZMS_FINISH - Sent ZFIN, waiting for ZFIN */ + +static const struct zm_transition_s g_zms_finish[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_FIN, true, ZMS_DONE, zms_xfrdone}, + {ZME_NAK, true, ZMS_FINISH, zms_finish}, + {ZME_RINIT, true, ZMS_FINISH, zms_finish}, + {ZME_ABORT, true, ZMS_FINISH, zms_abort}, + {ZME_FERR, true, ZMS_FINISH, zms_abort}, + {ZME_TIMEOUT, false, ZMS_FINISH, zms_timeout}, + {ZME_ERROR, false, ZMS_FINISH, zms_error} +}; + +/* Events handled in state ZMS_COMMAND - Waiting for command data */ + +static struct zm_transition_s g_zms_command[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_DATARCVD, false, ZMS_COMMAND, zms_ignore}, + {ZME_TIMEOUT, false, ZMS_COMMAND, zms_cmdto}, + {ZME_ERROR, false, ZMS_COMMAND, zms_error} +}; + +/* Events handled in state ZMS_MESSAGE - Waiting for stderr data */ + +static struct zm_transition_s g_zms_stderr[] = +{ + {ZME_SINIT, false, ZMS_START, zms_attention}, + {ZME_DATARCVD, false, ZMS_MESSAGE, zms_stderrdata}, + {ZME_TIMEOUT, false, ZMS_MESSAGE, zms_cmdto}, + {ZME_ERROR, false, ZMS_MESSAGE, zms_error} +}; + +/* Events handled in state ZMS_DONE - Finished with transfer */ + +static struct zm_transition_s g_zms_done[] = +{ + {ZME_TIMEOUT, false, ZMS_DONE, zms_doneto}, + {ZME_ERROR, false, ZMS_DONE, zms_error} +}; + +/* State x Event table for Zmodem receive. The order of states must + * exactly match the order defined in enum zms_e + */ + +static FAR const struct zm_transition_s * const g_zms_evtable[] = +{ + g_zms_start, /* ZMS_START - ZRQINIT sent, waiting for ZRINIT from receiver */ + g_zms_init, /* ZMS_INITACK - Received ZRINIT, sent ZSINIT, waiting for ZACK */ + g_zms_filewait, /* ZMS_FILEWAIT - Sent file header, waiting for ZRPOS */ + g_zms_crcwait, /* ZMS_CRCWAIT - Sent file CRC, waiting for ZRPOS response */ + g_zms_sending, /* ZMS_SENDING - Sending data subpackets, ready for interrupt */ + g_zms_sendwait, /* ZMS_SENDWAIT - Waiting for ZACK */ + g_zms_senddone, /* ZMS_SENDDONE - File sent, need to send ZEOF */ + g_zms_sendeof, /* ZMS_SENDEOF - Sent ZEOF, waiting for ZACK */ + g_zms_finish, /* ZMS_FINISH - Sent ZFIN, waiting for ZFIN */ + g_zms_command, /* ZMS_COMMAND - Waiting for command data */ + g_zms_stderr, /* ZMS_MESSAGE - Waiting for message from receiver */ + g_zms_done /* ZMS_DONE - Finished with transfer */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: zms_rinit + * + * Description: + * Received ZRINIT. Usually received while in start state, this can + * also be an attempt to resync after a protocol failure. + * + ****************************************************************************/ + +static int zms_rinit(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + uint16_t rcaps; + + zmdbg("ZMS_STATE %d\n", pzm->state); + + /* hdrdata[0] is the header type; header[1-4] is payload: + * + * F0 and F1 contain the bitwise OR of the receiver capability flags + * P0 and ZP1 contain the size of the receiver's buffer in bytes (or 0 + * if nonstop I/O is allowed. + */ + + pzms->rcvmax = (uint16_t)pzm->hdrdata[2] << 8 | (uint16_t)pzm->hdrdata[1]; + rcaps = (uint16_t)pzm->hdrdata[3] << 8 | (uint16_t)pzm->hdrdata[4]; + + /* Set flags associated with the capabilities */ + + rcaps &= ~(ZM_FLAG_CRC32 | ZM_FLAG_ESCCTRL); + if ((rcaps & CANFC32) != 0) + { + pzm->flags |= ZM_FLAG_CRC32; + } + + if ((rcaps & ESCCTL) != 0) + { + pzm->flags |= ZM_FLAG_ESCCTRL; + } + + /* Enable hardware flow control if we will be streaming */ + +#ifdef CONFIG_SYSTEM_ZMODEM_FULLSTREAMING + (void)zms_hwflowcontrol(pzmr->cmn.remfd, true); +#endif + +#if defined(CONFIG_SYSTEM_ZMODEM_SENDSAMPLE) || defined(CONFIG_SYSTEM_ZMODEM_SENDATTN) + if ((rcaps & (CANFDX | CANOVIO)) == (CANFDX | CANOVIO) && pzms->rcvmax == 0) + { + pzms->strtype = ZCRCG; + } + else +#else + if ((rcaps & (CANFDX | CANOVIO)) == (CANFDX | CANOVIO) && pzms->rcvmax == 0) + { + pzms->strtype = ZCRCQ; + } + else +#endif + { + pzms->strtype = ZCRCG; + } + +#ifdef CONFIG_SYSTEM_ZMODEM_ALWAYSSINT + return zms_sendzsinit(pzm); +#else +# ifdef CONFIG_SYSTEM_ZMODEM_SENDATTN + if (pzms->attn != NULL) + { + return zms_sendzsinit(pzm); + } + else +# endif + { + return ZM_XFRDONE; + } +#endif +} + +/**************************************************************************** + * Name: zms_attention + * + * Description: + * Received ZSINIT. The receiver wants something. Set the interrupt flag + * and handle this later in zms_sendpacket(). + * + ****************************************************************************/ + +static int zms_attention(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d\n", pzm->state); + pzm->flags |= ZM_FLAG_INTERRUPT; + return OK; +} + +/**************************************************************************** + * Name: zms_challenge + * + * Description: + * Answer challenge from receiver + * + ****************************************************************************/ + +static int zms_challenge(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d\n", pzm->state); + return zm_sendhexhdr(pzm, ZACK, pzm->hdrdata + 1); +} + +/**************************************************************************** + * Name: zms_abort + * + * Description: + * Receiver has cancelled + * + ****************************************************************************/ + +static int zms_abort(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d\n", pzm->state); + return zm_sendhexhdr(pzm, ZFIN, g_zeroes); +} + +/**************************************************************************** + * Name: zms_ignore + * + * Description: + * Ignore the header + * + ****************************************************************************/ + +static int zms_ignore(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d\n", pzm->state); + return OK; +} + +/**************************************************************************** + * Name: zms_command + * + * Description: + * Remote command received -- refuse it. + * + ****************************************************************************/ + +static int zms_command(FAR struct zm_state_s *pzm) +{ + uint8_t rbuf[4]; + + zmdbg("ZMS_STATE %d\n", pzm->state); + + rbuf[0] = EPERM; + rbuf[1] = 0; + rbuf[2] = 0; + rbuf[3] = 0; + return zm_sendhexhdr(pzm, ZCOMPL, rbuf); +} + +/**************************************************************************** + * Name: zms_message + * + * Description: + * The remote system wants to put a message on stderr + * + ****************************************************************************/ + +static int zms_message(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d\n", pzm->state); + zm_readstate(pzm); + return OK; +} + +/**************************************************************************** + * Name: zms_stderrdata + * + * Description: + * The remote system wants to put a message on stderr + * + ****************************************************************************/ + +static int zms_stderrdata(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d\n", pzm->state); + pzm->rcvbuf[pzm->rcvndx] = '\0'; + fprintf(stderr, "Message: %s", (char*)pzm->rcvbuf); + return OK; +} + +/**************************************************************************** + * Name: zms_initdone + * + * Description: + * Received ZRINIT, sent ZRINIT, waiting for ZACK, ZACK received. This + * completes the initialization sequence. Returning ZM_XFRDONE will + * alloc zm_initialize() to return. + * + ****************************************************************************/ + +static int zms_initdone(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d->%d\n", pzm->state, ZMS_DONE); + pzm->state = ZMS_DONE; + return ZM_XFRDONE; +} + +/**************************************************************************** + * Name: zms_sendzsinit + * + * Description: + * The remote system wants to put a message on stderr + * + ****************************************************************************/ + +static int zms_sendzsinit(FAR struct zm_state_s *pzm) +{ +#ifdef CONFIG_SYSTEM_ZMODEM_SENDATTN + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + FAR char *at = (pzms->attn != NULL) ? pzms->attn : ""; +#endif + int ret; + + /* Change to ZMS_INITACK state */ + + zmdbg("ZMS_STATE %d->%d\n", pzm->state, ZMS_INITACK); + pzm->state = ZMS_INITACK; + + /* Send the ZSINIT header (optional) + * + * Paragraph 11.3 ZSINIT. "The Sender sends flags followed by a binary + * data subpacket terminated with ZCRCW." + */ + + ret = zm_sendbinhdr(pzm, ZSINIT, g_zeroes); + if (ret >= 0) + { + /* Paragraph 11.3 "The data subpacket contains the null terminated + * Attn sequence, maximum length 32 bytes including the terminating + * null." + * + * We expect a ZACK next. + */ + +#ifdef CONFIG_SYSTEM_ZMODEM_SENDATTN + /* Send the NUL-terminated attention string */ + + ret = zm_senddata(pzm, (FAR uint8_t *)at, strlen(at) + 1); +#else + /* Send a null string */ + + ret = zm_senddata(pzm, g_zeroes, 1); +#endif + } + + return ret; +} + +/**************************************************************************** + * Name: zms_sendfilename + * + * Description: + * Send ZFILE header and filename. Wait for a response from receiver. + * + ****************************************************************************/ + +static int zms_sendfilename(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + FAR uint8_t *ptr = pzm->scratch; + int len; + int ret; + + zmdbg("ZMS_STATE %d->%d\n", pzm->state, ZMS_FILEWAIT); + + pzm->state = ZMS_FILEWAIT; + ret = zm_sendbinhdr(pzm, ZFILE, pzms->fflags); + if (ret < 0) + { + zmdbg("ERROR: zm_sendbinhdr failed: %d\n", ret); + return ret; + } + + /* Paragraph 13: + * Pathname + * The pathname (conventionally, the file name) is sent as a null + * terminated ASCII string. + */ + + len = strlen(pzms->rfilename); + memcpy(ptr, pzms->rfilename, len + 1); + ptr += len + 1; + + /* Paragraph 13: + * + * Length + * The file length ... is stored as a decimal string counting the + * number of data bytes in the file. + * Modification Date + * A single space separates the modification date from the file + * length. ... The mod date is sent as an octal number giving ... + * A date of 0 implies the modification date is unknown and should be + * left as the date the file is received. + * File Mode + * A single space separates the file mode from the modification date. + * The file mode is stored as an octal string. Unless the file + * originated from a Unix system, the file mode is set to 0. + * Serial Number + * A single space separates the serial number from the file mode. + * The serial number of the transmitting program is stored as an + * octal string. Programs which do not have a serial number should + * omit this field, or set it to 0. + * Number of Files Remaining + * Iff the number of files remaining is sent, a single space separates + * this field from the previous field. This field is coded as a + * decimal number, and includes the current file. + * Number of Bytes Remaining + * Iff the number of bytes remaining is sent, a single space + * separates this field from the previous field. This field is coded + * as a decimal number, and includes the current file + * File Type + * Iff the file type is sent, a single space separates this field from + * the previous field. This field is coded as a decimal number. + * Currently defined values are: + * + * 0 Sequential file - no special type + * 1 Other types to be defined. + * + * The file information is terminated by a null. + */ + +#ifdef CONFIG_SYSTEM_ZMODEM_TIMESTAMPS + sprintf((FAR char *)ptr, "%ld %lo 0 %d 1 %ld 0", + (unsigned long)pzms->filesize, (unsigned long)pzms->timestamp, + CONFIG_SYSTEM_ZMODEM_SERIALNO, (unsigned long)pzms->filesize); +#else + sprintf((FAR char *)ptr, "%ld 0 0 %d 1 %ld 0", + (unsigned long)pzms->filesize, CONFIG_SYSTEM_ZMODEM_SERIALNO, + (unsigned long)pzms->filesize); +#endif + + ptr += strlen((char *)ptr); + *ptr++ = '\0'; + + len = ptr - pzm->scratch; + DEBUGASSERT(len < CONFIG_SYSTEM_ZMODEM_SNDBUFSIZE); + return zm_senddata(pzm, pzm->scratch, len); +} + +/**************************************************************************** + * Name: zms_fileskip + * + * Description: + * The entire file has been transferred, ZEOF has been sent to the remote + * receiver, and the receiver has returned ZRINIT. Time to send ZFIN. + * + ****************************************************************************/ + +static int zms_endoftransfer(FAR struct zm_state_s *pzm) +{ + zmdbg("ZMS_STATE %d send ZFIN\n", pzm->state); + pzm->state = ZMS_FINISH; + + return zm_sendhexhdr(pzm, ZFIN, g_zeroes); +} + +/**************************************************************************** + * Name: zms_fileskip + * + * Description: + * Received ZSKIP, receiver doesn't want this file. + * + ****************************************************************************/ + +static int zms_fileskip(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + + zmdbg("ZMS_STATE %d\n", pzm->state); + close(pzms->infd); + pzms->infd = -1; + return ZM_XFRDONE; +} + +/**************************************************************************** + * Name: zms_sendfiledata + * + * Description: + * Send a chunk of file data in response to a ZRPOS. This may be followed + * followed by a ZCRCE, ZCRCG, ZCRCQ or ZCRCW dependinig on protocol flags. + * + ****************************************************************************/ + +static int zms_sendfiledata(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + + pzm->flags &= ~ZM_FLAG_WAIT; + return zms_startfiledata(pzms); +} + +/**************************************************************************** + * Name: zms_sendpacket + * + * Description: + * Send a chunk of file data in response to a ZRPOS. This may be followed + * followed by a ZCRCE, ZCRCG, ZCRCQ or ZCRCW dependinig on protocol flags. + * + * This function is called after ZDATA is send, after previous data was + * ACKed, and on certain error conditions where it is necessary to re-send + * the file data. + * + ****************************************************************************/ + +static int zms_sendpacket(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + ssize_t nwritten; + int32_t unacked; + bool bcrc32; + uint32_t crc; + uint8_t by[4]; + uint8_t *ptr; + uint8_t type; + bool wait = false; + int sndsize; + int pktsize; + int ret; + int i; + + /* ZCRCE: CRC next, frame ends, header follows ZCRCG: CRC next, frame + * continues nonstop ZCRCQ: CRC next, send ZACK, frame continues nonstop + * ZCRCW: CRC next, send ZACK, frame ends, header follows. + */ + + if ((pzm->flags & ZM_FLAG_INTERRUPT) != 0) + { + /* Receiver sent an interrupt. Enter a wait state and see what + * they want. Next header *should* be ZRPOS. + */ + + zmdbg("ZMS_STATE %d->%d: Interrupt\n", pzm->state, ZMS_SENDWAIT); + + pzm->state = ZMS_SENDWAIT; + pzm->timeout = CONFIG_SYSTEM_ZMODEM_RESPTIME; + pzm->flags &= ~ZM_FLAG_INTERRUPT; + return 0; + } + + /* This is the number of byte left in the file to be sent */ + + sndsize = pzms->filesize - pzms->offset; + + /* This is the nubmer of bytes that have been sent but not yet ackowledged. */ + + unacked = pzms->offset - pzms->lastoffs; + + /* Can we still send? If so, how much? If rcvmax is zero, then the + * remote can handle full streaming and we never have to wait. Otherwise, + * we have to restrict the total number of unacknowledged bytes to rcvmax. + */ + + zmdbg("sndsize: %d unacked: %d rcvmax: %d\n", + sndsize, unacked, pzms->rcvmax); + + if (pzms->rcvmax != 0) + { + /* If we were to send 'sndsize' more bytes, would that exceed recvmax? */ + + if (sndsize + unacked > pzms->rcvmax) + { + /* Yes... clip the maximum so that we stay within that limit */ + + int maximum = pzms->rcvmax - unacked; + if (sndsize < maximum) + { + sndsize = maximum; + } + + wait = true; + zmdbg("Clipped sndsize: %d\n", sndsize); + } + } + + /* Can we send anything? */ + + if (sndsize <= 0) + { + /* No, not now. Keep waiting */ + + zmdbg("ZMS_STATE %d->%d\n", pzm->state, ZMS_SENDWAIT); + + pzm->state = ZMS_SENDWAIT; + pzm->timeout = CONFIG_SYSTEM_ZMODEM_RESPTIME; + return OK; + } + + /* Determine what kind of packet to send */ + + if ((pzm->flags & ZM_FLAG_WAIT) != 0) + { + type = ZCRCW; + pzm->flags &= ~ZM_FLAG_WAIT; + } + else if (wait) + { + type = ZCRCW; + } + else + { + type = pzms->strtype; + } + + /* Read characters from file and put into buffer until buffer is full or + * file is exhausted + */ + + bcrc32 = ((pzm->flags & ZM_FLAG_CRC32) != 0); + crc = bcrc32 ? 0xffffffff : 0; + pzm->flags &= ~ZM_FLAG_ATSIGN; + + ptr = pzm->scratch; + pktsize = 0; + + while (pktsize <= (CONFIG_SYSTEM_ZMODEM_SNDBUFSIZE - 10) && + (ret = zm_getc(pzms->infd)) != EOF) + { + /* Add the new value to the accumulated CRC */ + + uint8_t ch = (uint8_t)ret; + if (!bcrc32) + { + crc = (uint32_t)crc16part(&ch, 1, (uint16_t)crc); + } + else + { + crc = crc32part(&ch, 1, crc); + } + + /* Put the character into the buffer, escaping as necessary */ + + ptr = zm_putzdle(pzm, ptr, ch); + + /* Recalculate the accumulated packet size to handle expansion due to + * escaping. + */ + + pktsize = (int32_t)(ptr - pzm->scratch); + + /* And increment the file offset */ + + pzms->offset++; + } + + /* If we've reached file end, a ZEOF header will follow. If there's room + * in the outgoing buffer for it, end the packet with ZCRCE and append the + * ZEOF header. If there isn't room, we'll have to do a ZCRCW + */ + + pzm->flags &= ~ZM_FLAG_EOF; + if (ret == EOF) + { + pzm->flags |= ZM_FLAG_EOF; + if (wait || (pzms->rcvmax != 0 && pktsize < 24)) + { + type = ZCRCW; + } + else + { + type = ZCRCE; + } + } + + /* Save the ZDLE in the transmit buffer */ + + *ptr++ = ZDLE; + + /* Save the type */ + + if (!bcrc32) + { + crc = (uint32_t)crc16part(&type, 1, (uint16_t)crc); + } + else + { + crc = crc32part(&type, 1, crc); + } + + *ptr++ = type; + + /* Update the CRC and put the CRC in the transmit buffer */ + + if (!bcrc32) + { + crc = (uint32_t)crc16part(g_zeroes, 2, (uint16_t)crc); + ptr = zm_putzdle(pzm, ptr, (crc >> 8) & 0xff); + ptr = zm_putzdle(pzm, ptr, crc & 0xff); + } + else + { + crc = ~crc; + for (i = 0; i < 4; i++, crc >>= 8) + { + ptr = zm_putzdle(pzm, ptr, crc & 0xff); + } + } + + /* Get the final packet size */ + + pktsize = ptr - pzm->scratch; + DEBUGASSERT(pktsize < CONFIG_SYSTEM_ZMODEM_SNDBUFSIZE); + + /* And send the packet */ + + dbg("Sending %d bytes. New offset: %ld\n", + pktsize, (unsigned long)pzms->offset); + + nwritten = zm_remwrite(pzm->remfd, pzm->scratch, pktsize); + if (nwritten < 0) + { + zmdbg("ERROR: zm_remwrite failed: %d\n", (int)nwritten); + return (int)nwritten; + } + + /* Then do what? That depends on the type of the transfer */ + + switch (type) + { + /* That was the last packet. Send ZCRCE to indicate the end of file */ + + case ZCRCE: /* CRC next, frame ends, header follows */ + zmdbg("ZMS_STATE %d->%d: ZCRCE\n", pzm->state, ZMS_SENDEOF); + + pzm->state = ZMS_SENDEOF; + pzm->timeout = CONFIG_SYSTEM_ZMODEM_RESPTIME; + zm_be32toby(pzms->offset, by); + return zm_sendhexhdr(pzm, ZEOF, by); + + /* We need to want for ZACK */ + + case ZCRCW: /* CRC next, send ZACK, frame ends */ + if ((pzm->flags & ZM_FLAG_EOF) != 0) + { + zmdbg("ZMS_STATE %d->%d: EOF\n", pzm->state, ZMS_SENDDONE); + pzm->state = ZMS_SENDDONE; + } + else + { + zmdbg("ZMS_STATE %d->%d: Not EOF\n", pzm->state, ZMS_SENDWAIT); + pzm->state = ZMS_SENDWAIT; + } + + pzm->timeout = CONFIG_SYSTEM_ZMODEM_RESPTIME; + break; + + /* No response is expected */ + + case ZCRCG: /* CRC next, frame continues nonstop */ + case ZCRCQ: /* CRC next, send ZACK, frame continues nonstop */ + default: + zmdbg("ZMS_STATE %d->%d: Default\n", pzm->state, ZMS_SENDING); + + pzm->state = ZMS_SENDING; + pzm->timeout = 0; + break; + } + + return OK; +} + +/**************************************************************************** + * Name: zms_filecrc + * + * Description: + * ZFILE has been sent and waiting for ZCRC. ZRPOS received. + * + ****************************************************************************/ + +static int zms_filecrc(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + uint8_t by[4]; + uint32_t crc; + + crc = zm_filecrc(pzm, pzms->filename); + zmdbg("ZMS_STATE %d: CRC %08x\n", pzm->state, crc); + + zm_be32toby(crc, by); + return zm_sendhexhdr(pzm, ZCRC, by); +} + +/**************************************************************************** + * Name: zms_sendack + * + * Description: + * An ACK arrived while transmitting data. Update last known receiver + * offset, and try to send more data. + * + ****************************************************************************/ + +static int zms_sendack(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + off_t offset; + + /* Paragraph 11.4 ZACK. Acknowledgment to a ZSINIT frame, ..., ZCRCQ or + * ZCRCW data subpacket. ZP0 to ZP3 contain file offset. + */ + + offset = zm_bytobe32(pzm->hdrdata + 1); + + if (offset > pzms->lastoffs) + { + pzms->lastoffs = offset; + } + + zmdbg("ZMS_STATE %d: offset: %ld\n", pzm->state, (unsigned long)pzms->offset); + return OK; +} + +/**************************************************************************** + * Name: zms_sendwaitack + * + * Description: + * An ACK arrived while waiting to transmit data. Update last known + * receiver offset, and try to send more data. + * + ****************************************************************************/ + +static int zms_sendwaitack(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + uint8_t by[4]; + off_t offset; + int ret; + + /* Paragraph 11.4 ZACK. Acknowledgment to a ZSINIT frame, ..., ZCRCQ or + * ZCRCW data subpacket. ZP0 to ZP3 contain file offset. + */ + + offset = zm_bytobe32(pzm->hdrdata + 1); + + if (offset > pzms->lastoffs) + { + pzms->lastoffs = offset; + } + + zmdbg("ZMS_STATE %d: offset: %ld\n", pzm->state, (unsigned long)offset); + + /* Now send the next data packet */ + + zm_be32toby(pzms->offset, by); + ret = zm_sendbinhdr(pzm, ZDATA, by); + if (ret != OK) + { + return ret; + } + + return zms_sendpacket(pzm); +} + +/**************************************************************************** + * Name: zms_sendnak + * + * Description: + * ZDATA header was corrupt. Start from beginning + * + ****************************************************************************/ + +static int zms_sendnak(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + off_t offset; + + /* Save the ZRPOS file offset */ + + pzms->offset = pzms->zrpos; + + /* TODO: What is the correct thing to do if lseek fails? Send ZEOF? */ + + offset = lseek(pzms->infd, pzms->offset, SEEK_SET); + if (offset == (off_t)-1) + { + int errorcode = errno; + + zmdbg("ERROR: Failed to seek to %ld: %d\n", + (unsigned long)pzms->offset, errorcode); + DEBUGASSERT(errorcode > 0); + return -errorcode; + } + + zmdbg("ZMS_STATE %d: offset: %ld\n", pzm->state, (unsigned long)pzms->offset); + + return zms_sendpacket(pzm); +} + +/**************************************************************************** + * Name: zms_sendrpos + * + * Description: + * Received ZRPOS while sending a file. Set the new offset and try again. + * + ****************************************************************************/ + +static int zms_sendrpos(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + + pzm->nerrors++; + pzm->flags |= ZM_FLAG_WAIT; + return zms_startfiledata(pzms); +} + +/**************************************************************************** + * Name: zms_senddoneack + * + * Description: + * ACK arrived after last file packet sent. Send the ZEOF + * + ****************************************************************************/ + +static int zms_senddoneack(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + uint8_t by[4]; + off_t offset; + + /* Paragraph 11.4 ZACK. Acknowledgment to a ZSINIT frame, ..., ZCRCQ or + * ZCRCW data subpacket. ZP0 to ZP3 contain file offset. + */ + + offset = zm_bytobe32(pzm->hdrdata + 1); + + if (offset > pzms->lastoffs) + { + pzms->lastoffs = offset; + } + + zmdbg("ZMS_STATE %d->%d: offset: %ld\n", + pzm->state, ZMS_SENDEOF, (unsigned long)pzms->offset); + + /* Now send the ZEOF */ + + pzm->state = ZMS_SENDEOF; + pzm->timeout = CONFIG_SYSTEM_ZMODEM_RESPTIME; + zm_be32toby(pzms->offset, by); + return zm_sendhexhdr(pzm, ZEOF, by); +} + +/**************************************************************************** + * Name: zms_resendeof + * + * Description: + * ACK arrived after last file packet sent. Send the ZEOF + * + ****************************************************************************/ + +static int zms_resendeof(FAR struct zm_state_s *pzm) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)pzm; + uint8_t by[4]; + + zm_be32toby(pzms->offset, by); + return zm_sendhexhdr(pzm, ZEOF, by); +} + +/**************************************************************************** + * Name: zms_xfrdone + * + * Description: + * Sent ZFIN, received ZFIN in response. This transfer is complete. + * We will not send the "OO" until the last file has been sent. + * + ****************************************************************************/ + +static int zms_xfrdone(FAR struct zm_state_s *pzm) +{ + zmdbg("Transfer complete\n"); + return ZM_XFRDONE; +} + +/**************************************************************************** + * Name: zms_finish + * + * Description: + * Sent ZFIN, received ZNAK or ZRINIT + * + ****************************************************************************/ + +static int zms_finish(FAR struct zm_state_s *pzm) +{ + return ZM_XFRDONE; +} + +/**************************************************************************** + * Name: zms_timeout + * + * Description: + * An timeout occurred in this state + * + ****************************************************************************/ + +static int zms_timeout(FAR struct zm_state_s *pzm) +{ + zmdbg("ERROR: Receiver did not respond\n"); + return -ETIMEDOUT; +} + +/**************************************************************************** + * Name: zms_cmdto + * + * Description: + * Timed out waiting for command or stderr data + * + ****************************************************************************/ + +static int zms_cmdto(FAR struct zm_state_s *pzm) +{ + zmdbg("ERROR: No command received\n"); + return -ETIMEDOUT; +} + +/**************************************************************************** + * Name: zms_doneto + * + * Description: + * Timed out in ZMS_DONE state + * + ****************************************************************************/ + +static int zms_doneto(FAR struct zm_state_s *pzm) +{ + zmdbg("Timeout if ZMS_DONE\n"); + return ZM_XFRDONE; +} + +/**************************************************************************** + * Name: zms_error + * + * Description: + * An unexpected event occurred in this state + * + ****************************************************************************/ + +static int zms_error(FAR struct zm_state_s *pzm) +{ + zmdbg("Unhandled event, header=%d\n", pzm->hdrdata[0]); + pzm->flags |= ZM_FLAG_WAIT; + return OK; +} + +/**************************************************************************** + * Name: zms_sendfiledata + * + * Description: + * Send a chunk of file data in response to a ZRPOS. This may be followed + * followed by a ZCRCE, ZCRCG, ZCRCQ or ZCRCW dependinig on protocol flags. + * + ****************************************************************************/ + +static int zms_startfiledata(FAR struct zms_state_s *pzms) +{ + off_t offset; + int ret; + + zmdbg("ZMS_STATE %d: offset %ld nerrors %d\n", + pzms->cmn.state, (unsigned long)pzms->offset, pzms->cmn.nerrors); + + /* Paragraph 8.2: "A ZRPOS header from the receiver initiates transmission + * of the file data starting at the offset in the file specified in the + * ZRPOS header." + */ + + pzms->zrpos = zm_bytobe32(pzms->cmn.hdrdata + 1); + pzms->offset = pzms->zrpos; + pzms->lastoffs = pzms->zrpos; + + /* See to the requested file position */ + + offset = lseek(pzms->infd, pzms->offset, SEEK_SET); + if (offset == (off_t)-1) + { + int errorcode = errno; + + zmdbg("ERROR: Failed to seek to %ld: %d\n", + (unsigned long)pzms->offset, errorcode); + DEBUGASSERT(errorcode > 0); + return -errorcode; + } + + /* Paragraph 8.2: "The sender sends a ZDATA binary header (with file + * position) followed by one or more data subpackets." + */ + + zmdbg("ZMS_STATE %d: Send ZDATA offset %ld\n", + pzms->cmn.state, (unsigned long)pzms->offset); + + ret = zm_sendbinhdr(&pzms->cmn, ZDATA, pzms->cmn.hdrdata + 1); + if (ret != OK) + { + return ret; + } + + return zms_sendpacket(&pzms->cmn); +} + +/**************************************************************************** + * Name: zms_sendfile + * + * Description: + * Begin transmission of a file + * + ****************************************************************************/ + +/* Called by user to begin transmission of a file */ + +static int zms_sendfile(FAR struct zms_state_s *pzms, FAR const char *filename, + FAR const char *rfilename, uint8_t f0, uint8_t f1) +{ + struct stat buf; + int ret; + + DEBUGASSERT(pzms && filename && rfilename); + zmdbg("filename: %s rfilename: %s f0: %02x f1: %02x\n", + filename, rfilename, f0, f1); + + /* TODO: The local file name *must* be an absolute patch for now. This if + * environment variables are supported, then any relative pathes could be + * extended using the contents of the current working directory CWD. + */ + + if (filename[0] != '/') + { + zmdbg("ERROR: filename must be an absolute path: %s\n", filename); + return -ENOSYS; + } + + /* Get information about the local file */ + + ret = stat(filename, &buf); + if (ret < 0) + { + int errorcode = errno; + DEBUGASSERT(errorcode > 0); + zmdbg("Failed to stat %s: %d\n", filename, errorcode); + return -errorcode; + } + + /* Open the local file for reading */ + + pzms->infd = open(filename, O_RDONLY); + if (pzms->infd < 0) + { + int errorcode = errno; + DEBUGASSERT(errorcode > 0); + zmdbg("Failed to open %s: %d\n", filename, errorcode); + return -errorcode; + } + + /* Initialize for the transfer */ + + pzms->cmn.flags &= ~ZM_FLAG_EOF; + pzms->filename = filename; + pzms->rfilename = rfilename; + DEBUGASSERT(pzms->filename && pzms->rfilename); + + pzms->fflags[3] = f0; + pzms->fflags[2] = f1; + pzms->fflags[1] = 0; + pzms->fflags[0] = 0; + pzms->offset = 0; + pzms->lastoffs = 0; + + pzms->filesize = buf.st_size; +#ifdef CONFIG_SYSTEM_ZMODEM_TIMESTAMPS + pzms->timestamp = buf.st_mtime; +#endif + + zmdbg("ZMS_STATE %d->%d\n", pzms->cmn.state, ZMS_FILEWAIT); + + pzms->cmn.state = ZMS_FILEWAIT; + + zmdbg("ZMS_STATE %d: Send ZFILE(%s)\n", pzms->cmn.state, pzms->rfilename); + return zms_sendfilename(&pzms->cmn); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: zms_initialize + * + * Description: + * Initialize for Zmodem send operation. The overall usage is as follows: + * + * 1) Call zms_initialize() to create the partially initialized struct + * zms_state_s instance. + * 2) Make any custom settings in the struct zms_state_s instance. + * 3) Create a stream instance to get the "file" to transmit and add + * the filename to pzms + * 4) Call zms_send() to transfer the file. + * 5) Repeat 3) and 4) to transfer as many files as desired. + * 6) Call zms_release() when the final file has been transferred. + * + * Input Parameters: + * remfd - The R/W file/socket descriptor to use for communication with the + * remote peer. + * + ****************************************************************************/ + +ZMSHANDLE zms_initialize(int remfd) +{ + FAR struct zms_state_s *pzms; + FAR struct zm_state_s *pzm; + ssize_t nwritten; + int ret; + + DEBUGASSERT(remfd >= 0); + + /* Allocate the instance */ + + pzms = (FAR struct zms_state_s *)zalloc(sizeof(struct zms_state_s)); + if (pzms) + { + pzm = &pzms->cmn; + pzm->evtable = g_zms_evtable; + pzm->state = ZMS_START; + pzm->pstate = PSTATE_IDLE; + pzm->psubstate = PIDLE_ZPAD; + pzm->remfd = remfd; + + /* Create a timer to handle timeout events */ + + ret = zm_timerinit(pzm); + if (ret < 0) + { + zmdbg("ERROR: zm_timerinit failed: %d\n", ret); + goto errout; + } + + /* Send "rz\r" to the remote end. + * + * Paragraph 8.1: "The sending program may send the string "rz\r" to + * invoke the receiving program from a possible command mode. The + * "rz" followed by carriage return activates a ZMODEM receive program + * or command if it were not already active. + */ + + nwritten = zm_remwrite(pzm->remfd, (uint8_t *) "rz\r", 3); + if (nwritten < 0) + { + zmdbg("ERROR: zm_remwrite failed: %d\n", (int)nwritten); + goto errout_with_timer; + } + + /* Send ZRQINIT + * + * Paragraph 8.1: "Then the sender may send a ZRQINIT header. The + * ZRQINIT header causes a previously started receive program to send + * its ZRINIT header without delay." + */ + + ret = zm_sendhexhdr(&pzms->cmn, ZRQINIT, g_zeroes); + if (ret < 0) + { + zmdbg("ERROR: zm_sendhexhdr failed: %d\n", ret); + goto errout_with_timer; + } + + /* Set up a timeout for the response */ + + pzm->timeout = CONFIG_SYSTEM_ZMODEM_RESPTIME; + zmdbg("ZMS_STATE %d sent ZRQINIT\n", pzm->state); + + /* Now drive the state machine by reading data from the remote peer + * and providing that data to the parser. zm_datapump runs until an + * irrecoverable error is detected or until the ZRQINIT is ACK-ed by + * the remote receiver. + */ + + ret = zm_datapump(&pzms->cmn); + if (ret < 0) + { + zmdbg("ERROR: zm_datapump failed: %d\n", ret); + goto errout_with_timer; + } + } + + return (ZMSHANDLE)pzms; + +errout_with_timer: + (void)zm_timerrelease(&pzms->cmn); +errout: + free(pzms); + return (ZMSHANDLE)NULL; +} + +/**************************************************************************** + * Name: zms_send + * + * Description: + * Send a file. + * + * Input Parameters: + * handle - Handle previoulsy returned by xms_initialize() + * filename - The name of the local file to transfer + * rfilename - The name of the remote file name to create + * option - Describes optional transfer behavior + * f1 - The F1 transfer flags + * skip - True: Skip if file not present at receiving end. + * + * Assumptions: + * The filename and rfilename pointers refer to memory that will persist + * at least until the transfer completes. + * + ****************************************************************************/ + +int zms_send(ZMSHANDLE handle, FAR const char *filename, + FAR const char *rfilename, enum zm_xfertype_e xfertype, + enum zm_option_e option, bool skip) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)handle; + uint8_t f1; + int ret; + + /* At this point either (1) zms_intiialize() has just been called or + * (2) the previous file has been sent. + */ + + DEBUGASSERT(pzms && filename && rfilename && pzms->cmn.state == ZMS_DONE); + + /* Set the ZMSKNOLOC option is so requested */ + + f1 = option; + if (skip) + { + f1 |= ZMSKNOLOC; + } + + /* Initiate sending of the file. This will open the source file, + * initialize data structures and set the ZMSS_FILEWAIT state. + */ + + ret = zms_sendfile(pzms, filename, rfilename, (uint8_t)xfertype, f1); + if (ret < 0) + { + zmdbg("ERROR: zms_sendfile failed: %d\n", ret); + return ret; + } + + /* Now drive the state machine by reading data from the remote peer + * and providing that data to the parser. zm_datapump runs until an + * irrecoverable error is detected or until the file is sent correctly. + */ + + return zm_datapump(&pzms->cmn); +} + +/**************************************************************************** + * Name: zms_release + * + * Description: + * Called by the user when there are no more files to send. + * + ****************************************************************************/ + +int zms_release(ZMSHANDLE handle) +{ + FAR struct zms_state_s *pzms = (FAR struct zms_state_s *)handle; + ssize_t nwritten; + int ret = OK; + + /* Send "OO" */ + + nwritten = zm_remwrite(pzms->cmn.remfd, (FAR const uint8_t*)"OO", 2); + if (nwritten < 0) + { + zmdbg("ERROR: zm_remwrite failed: %d\n", (int)nwritten); + ret = (int)nwritten; + } + + /* Release the timer resources */ + + (void)zm_timerrelease(&pzms->cmn); + + /* And free the Zmodem state structure */ + + free(pzms); + return ret; +} diff --git a/apps/system/zmodem/zm_state.c b/apps/system/zmodem/zm_state.c new file mode 100644 index 000000000..014e26ad5 --- /dev/null +++ b/apps/system/zmodem/zm_state.c @@ -0,0 +1,960 @@ +/**************************************************************************** + * system/zmodem/zm_state.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "The ZMODEM Inter Application File Transfer Protocol", Chuck Forsberg, + * Omen Technology Inc., October 14, 1988 + * + * This is an original work, but I want to make sure that credit is given + * where due: Parts of the state machine design were inspired by the + * Zmodem library of Edward A. Falk, dated January, 1995. License + * unspecified. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "zm.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* State-specific data receipt handlers */ + +static int zm_idle(FAR struct zm_state_s *pzm, uint8_t ch); +static int zm_header(FAR struct zm_state_s *pzm, uint8_t ch); +static int zm_data(FAR struct zm_state_s *pzm, uint8_t ch); +static int zm_finish(FAR struct zm_state_s *pzm, uint8_t ch); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: zm_event + * + * Description: + * This is the heart of the Zmodem state machine. Logic initiated by + * zm_parse() will detect events and, eventually call this function. + * This function will make the state transition, performing any action + * associated with the event. + * + ****************************************************************************/ + +static int zm_event(FAR struct zm_state_s *pzm, int event) +{ + FAR const struct zm_transition_s *ptr; + + zmdbg("ZM[R|S]_state: %d event: %d\n", pzm->state, event); + + /* Look up the entry associated with the event in the current state + * transition table. NOTE that each state table must be termined with a + * ZME_ERROR entry that provides indicates that the event was not + * expected. Thus, the following search will always be successful. + */ + + ptr = pzm->evtable[pzm->state]; + while (ptr->type != ZME_ERROR && ptr->type != event) + { + /* Skip to the next entry */ + + ptr++; + } + + zmdbg("Transition ZM[R|S]_state %d->%d discard: %d action: %p\n", + pzm->state, ptr->next, ptr->bdiscard, ptr->action); + + /* Perform the state transition */ + + pzm->state = ptr->next; + + /* Discard buffered data if so requrested */ + + if (ptr->bdiscard) + { + pzm->rcvlen = 0; + pzm->rcvndx = 0; + } + + /* And, finally, perform the associated action */ + + return ptr->action(pzm); +} + +/**************************************************************************** + * Name: zm_nakhdr + * + * Description: + * Send a NAK in response to a malformed or unsupported header. + * + ****************************************************************************/ + +static int zm_nakhdr(FAR struct zm_state_s *pzm) +{ + zmdbg("PSTATE %d:%d->%d.%d: NAKing\n", + pzm->pstate, pzm->psubstate, PSTATE_IDLE, PIDLE_ZPAD); + + /* Revert to the IDLE state */ + + pzm->pstate = PSTATE_IDLE; + pzm->psubstate = PIDLE_ZPAD; + + /* And NAK the header */ + + return zm_sendhexhdr(pzm, ZNAK, g_zeroes); +} + +/**************************************************************************** + * Name: zm_hdrevent + * + * Description: + * Process an event associated with a header. + * + ****************************************************************************/ + +static int zm_hdrevent(FAR struct zm_state_s *pzm) +{ + zmdbg("Received type: %d data: %02x %02x %02x %02x\n", + pzm->hdrdata[0], + pzm->hdrdata[1], pzm->hdrdata[2], pzm->hdrdata[3], pzm->hdrdata[4]); + zmdbg("PSTATE %d:%d->%d.%d\n", + pzm->pstate, pzm->psubstate, PSTATE_IDLE, PIDLE_ZPAD); + + /* Revert to the IDLE state */ + + pzm->pstate = PSTATE_IDLE; + pzm->psubstate = PIDLE_ZPAD; + + /* Verify the checksum. 16- or 32-bit? */ + + if (pzm->hdrfmt == ZBIN32) + { + uint32_t crc; + + /* Checksum is over 9 bytes: The header type, 4 data bytes, plus 4 CRC bytes */ + + crc = crc32part(pzm->hdrdata, 9, 0xffffffff); + if (crc != 0xdebb20e3) + { + zmdbg("ERROR: ZBIN32 CRC32 failure: %08x vs debb20e3\n", crc); + return zm_nakhdr(pzm); + } + } + else + { + uint16_t crc; + + /* Checksum is over 7 bytes: The header type, 4 data bytes, plus 2 CRC bytes */ + + crc = crc16part(pzm->hdrdata, 7, 0); + if (crc != 0) + { + zmdbg("ERROR: ZBIN/ZHEX CRC16 failure: %04x vs 0000\n", crc); + return zm_nakhdr(pzm); + } + } + + return zm_event(pzm, pzm->hdrdata[0]); +} + +/**************************************************************************** + * Name: zm_dataevent + * + * Description: + * Process an event associated with a header. + * + ****************************************************************************/ + +static int zm_dataevent(FAR struct zm_state_s *pzm) +{ + zmdbg("Received type: %d length: %d\n", pzm->pkttype, pzm->pktlen); + zmdbg("PSTATE %d:%d->%d.%d\n", + pzm->pstate, pzm->psubstate, PSTATE_IDLE, PIDLE_ZPAD); + + /* Revert to the IDLE state */ + + pzm->pstate = PSTATE_IDLE; + pzm->psubstate = PIDLE_ZPAD; + + /* Verify the checksum. 16- or 32-bit? */ + + if (pzm->hdrfmt == ZBIN32) + { + uint32_t crc; + + crc = crc32part(pzm->pktbuf, pzm->pktlen, 0xffffffff); + if (crc != 0xdebb20e3) + { + zmdbg("ERROR: ZBIN32 CRC32 failure: %08x vs debb20e3\n", crc); + pzm->flags &= ~ZM_FLAG_CRKOK; + } + else + { + pzm->flags |= ZM_FLAG_CRKOK; + } + } + else + { + uint16_t crc; + + crc = crc16part(pzm->pktbuf, pzm->pktlen, 0); + if (crc != 0) + { + zmdbg("ERROR: ZBIN/ZHEX CRC16 failure: %04x vs 0000\n", crc); + pzm->flags &= ~ZM_FLAG_CRKOK; + } + else + { + pzm->flags |= ZM_FLAG_CRKOK; + } + } + + return zm_event(pzm, ZME_DATARCVD); +} + +/**************************************************************************** + * Name: zm_idle + * + * Description: + * Data has been received in state PSTATE_IDLE. In this state we are + * looking for the beginning of a header indicated by the receipt of + * ZDLE. We skip over ZPAD characters and flush the received buffer in + * the case where anything else is received. + * + ****************************************************************************/ + +static int zm_idle(FAR struct zm_state_s *pzm, uint8_t ch) +{ + switch (ch) + { + /* One or more ZPAD characters must precede the ZDLE */ + + case ZPAD: + { + /* The ZDLE character is expected next */ + + zmdbg("PSTATE %d:%d->%d.%d\n", + pzm->pstate, pzm->psubstate, pzm->pstate, PIDLE_ZDLE); + + pzm->psubstate = PIDLE_ZDLE; + } + break; + + /* ZDLE indicates the beginning of a header. */ + + case ZDLE: + + /* Was the ZDLE preceded by ZPAD[s]? If not, fall through and treat + * as the default case. + */ + + if (pzm->psubstate == PIDLE_ZDLE) + { + zmdbg("PSTATE %d:%d->%d.%d\n", + pzm->pstate, pzm->psubstate, PSTATE_HEADER, PHEADER_FORMAT); + + pzm->pstate = PSTATE_HEADER; + pzm->psubstate = PHEADER_FORMAT; + break; + } + + /* Unexpected character. Wait for the next ZPAD to get us */ + + default: + if (pzm->psubstate != PIDLE_ZPAD) + { + zmdbg("PSTATE %d:%d->%d.%d\n", + pzm->pstate, pzm->psubstate, pzm->pstate, PIDLE_ZPAD); + + pzm->psubstate = PIDLE_ZPAD; + } + break; + } + + return OK; +} + +/**************************************************************************** + * Name: zm_header + * + * Description: + * Data has been received in state PSTATE_HEADER (i.e., ZDLE was received + * in PSTAT_IDLE). + * + * The following headers are supported: + * + * 16-bit Binary: + * ZPAD ZDLE ZBIN type f3/p0 f2/p1 f1/p2 f0/p3 crc-1 crc-2 + * Payload length: 7 (type, 4 bytes data, 2 byte CRC) + * 32-bit Binary: + * ZPAD ZDLE ZBIN32 type f3/p0 f2/p1 f1/p2 f0/p3 crc-1 crc-2 crc-3 crc-4 + * Payload length: 9 (type, 4 bytes data, 4 byte CRC) + * Hex: + * ZPAD ZPAD ZDLE ZHEX type f3/p0 f2/p1 f1/p2 f0/p3 crc-1 crc-2 CR LF [XON] + * Payload length: 16 (14 hex digits, cr, lf, ignoring optional XON) + * + ****************************************************************************/ + +static int zm_header(FAR struct zm_state_s *pzm, uint8_t ch) +{ + /* ZDLE encountered in this state means that the following character is + * escaped. + */ + + if (ch == ZDLE && (pzm->flags & ZM_FLAG_ESC) == 0) + { + /* Indicate that we are beginning the escape sequence and return */ + + pzm->flags |= ZM_FLAG_ESC; + return OK; + } + + /* Handle the escaped character in an escape sequence */ + + if ((pzm->flags & ZM_FLAG_ESC) != 0) + { + switch (ch) + { + /* Two special cases */ + + case ZRUB0: + ch = ASCII_DEL; + break; + + case ZRUB1: + ch = 0xff; + break; + + /* The typical case: Toggle bit 6 */ + + default: + ch ^= 0x40; + break; + } + + /* We are no longer in an escape sequence */ + + pzm->flags &= ~ZM_FLAG_ESC; + } + + /* Now handle the next character, escaped or not, according to the current + * PSTATE_HEADER substate. + */ + + switch (pzm->psubstate) + { + /* Waiting for the header format {ZBIN, ZBIN32, ZHEX} */ + + case PHEADER_FORMAT: + { + switch (ch) + { + /* Supported header formats */ + + case ZHEX: + case ZBIN: + case ZBIN32: + { + /* Save the header format character. Next we expect the header + * data payload beginning with the header type. + */ + + pzm->hdrfmt = ch; + pzm->psubstate = PHEADER_PAYLOAD; + pzm->hdrndx = 0; + } + break; + + default: + { + /* Unrecognized header format. */ + + return zm_nakhdr(pzm); + } + } + } + break; + + /* Waiting for header payload */ + + case PHEADER_PAYLOAD: + { + int ndx = pzm->hdrndx; + + switch (pzm->hdrfmt) + { + /* Supported header formats */ + + case ZHEX: + { + if (!isxdigit(ch)) + { + return zm_nakhdr(pzm); + } + + /* Save the MS nibble; setup to receive the LS nibble. Index + * is not incremented. + */ + + pzm->hdrdata[ndx] = zm_decnibble(ch) << 4; + pzm->psubstate = PHEADER_LSPAYLOAD; + } + break; + + case ZBIN: + case ZBIN32: + { + /* Save the payload byte and increment the index. */ + + pzm->hdrdata[ndx] = ch; + ndx++; + + /* Check if the full header payload has bee buffered. + * + * The ZBIN format uses 16-bit CRC so the binary length of the + * full payload is 1+4+2 = 7 bytes; the ZBIN32 uses a 32-bit CRC + * so the binary length of the payload is 1+4+4 = 9 bytes; + */ + + if (ndx >= 9 || (pzm->hdrfmt == ZBIN && ndx >= 7)) + { + return zm_hdrevent(pzm); + } + else + { + /* Setup to receive the next byte */ + + pzm->psubstate = PHEADER_PAYLOAD; + pzm->hdrndx = ndx; + } + } + break; + + default: /* Should not happen */ + break; + } + } + break; + + /* Waiting for LS nibble header type (ZHEX only) */ + + case PHEADER_LSPAYLOAD: + { + int ndx = pzm->hdrndx; + + if (pzm->hdrfmt == ZHEX && isxdigit(ch)) + { + /* Save the LS nibble and increment the index. */ + + pzm->hdrdata[ndx] |= zm_decnibble(ch); + ndx++; + + /* The ZHEX format uses 16-bit CRC. So the binary length + * of the sequence is 1+4+2 = 7 bytes. + */ + + if (ndx >= 7) + { + return zm_hdrevent(pzm); + } + else + { + /* Setup to receive the next MS nibble */ + + pzm->psubstate = PHEADER_PAYLOAD; + pzm->hdrndx = ndx; + } + } + else + { + return zm_nakhdr(pzm); + } + } + break; + } + + return OK; +} + +/**************************************************************************** + * Name: zm_data + * + * Description: + * Data has been received in state PSTATE_DATA. PSTATE_DATA is set by + * Zmodem transfer logic when it exepects to received data from the + * remote peer. + * + * FORMAT: + * xx xx xx xx ... xx ZDLE crc-1 crc-2 [crc-3 crc-4] + * + * Where xx is binary data (that may be escaped). The 16- or 32-bit CRC + * is selected based on a preceding header. ZHEX data packets are not + * supported. + * + * When setting pstate to PSTATE_DATA, it is also expected that the + * following initialization is performed: + * + * - The crc value is initialized appropriately + * - ncrc is set to zero. + * - pktlen is set to zero + * + ****************************************************************************/ + +static int zm_data(FAR struct zm_state_s *pzm, uint8_t ch) +{ + /* ZDLE encountered in this state means that the following character is + * escaped. Escaped characters may appear anywhere within the data packet. + */ + + if (ch == ZDLE && (pzm->flags & ZM_FLAG_ESC) == 0) + { + /* Indicate that we are beginning the escape sequence and return */ + + pzm->flags |= ZM_FLAG_ESC; + return OK; + } + + /* Make sure that there is space for another byte in the packet buffer */ + + if (pzm->pktlen >= CONFIG_SYSTEM_ZMODEM_PKTBUFSIZE) + { + zmdbg("ERROR: The packet buffer is full\n"); + return -ENOSPC; + } + + /* Handle the escaped character in an escape sequence */ + + if ((pzm->flags & ZM_FLAG_ESC) != 0) + { + switch (ch) + { + /* The data packet type may immediately follow the ZDLE in PDATA_READ + * substate. + */ + + case ZCRCW: /* Data packet (Non-streaming, ZACK response expected) */ + case ZCRCE: /* Data packet (End-of-file, no response unless an error occurs) */ + case ZCRCG: /* Data packet (Full streaming, no response) */ + case ZCRCQ: /* Data packet (ZACK response expected) */ + { + /* Save the packet type, change substates, and set of count that + * indicates the nubmer of bytes still to be added to the packet + * buffer: + * + * ZBIN: 1+2 = 3 + * ZBIN32: 1+4 = 5 + */ + + pzm->pkttype = ch; + pzm->psubstate = PDATA_CRC; + pzm->ncrc = (pzm->hdrfmt == ZBIN32) ? 5 : 3; + } + break; + + /* Some special cases */ + + case ZRUB0: + ch = ASCII_DEL; + break; + + case ZRUB1: + ch = 0xff; + break; + + /* The typical case: Toggle bit 6 */ + + default: + ch ^= 0x40; + break; + } + + /* We are no longer in an escape sequence */ + + pzm->flags &= ~ZM_FLAG_ESC; + } + + /* Transfer received data from the I/O buffer to the packet buffer. + * Accumulate the CRC for the received data. This includes the data + * payload plus the packet type code plus the CRC itself. + */ + + pzm->pktbuf[pzm->pktlen++] = ch; + if (pzm->ncrc == 1) + { + /* We are at the end of the packet. Check the CRC and post the event */ + + zm_dataevent(pzm); + } + else if (pzm->ncrc > 1) + { + /* We are still parsing the CRC. Decrement the count of CRC bytes + * remaining. + */ + + pzm->ncrc--; + } + + return OK; +} + +/**************************************************************************** + * Name: zm_finish + * + * Description: + * Data has been received in state PSTATE_FINISH. Juse wait for "OO" + * + ****************************************************************************/ + +static int zm_finish(FAR struct zm_state_s *pzm, uint8_t ch) +{ + /* Wait for "OO" */ + + if (ch == 'O') + { + /* Have we seen the second '0'? */ + + if (pzm->psubstate == PFINISH_2NDO) + { + /* Yes.. then we are finished */ + + return ZM_XFRDONE; + } + else + { + /* No.. this was the first */ + + pzm->psubstate = PFINISH_2NDO; + } + } + else + { + /* Reset. We have not seen the first 'O' of the pair */ + + pzm->psubstate = PFINISH_1STO; + } + + return OK; +} + +/**************************************************************************** + * Name: zm_parse + * + * Description: + * New data from the remote peer is available in pzm->rcvbuf. The number + * number of bytes of new data is given by rcvlen. + * + * This function will parse the data in the buffer and, based on the + * current state and the contents of the buffer, will drive the Zmodem + * state machine. + * + ****************************************************************************/ + +static int zm_parse(FAR struct zm_state_s *pzm, size_t rcvlen) +{ + uint8_t ch; + int ret; + + DEBUGASSERT(pzm && rcvlen < CONFIG_SYSTEM_ZMODEM_RCVBUFSIZE); + zm_dumpbuffer("Received", pzm->rcvbuf, rcvlen); + + /* We keep a copy of the length and buffer index in the state structure. + * This is only so that deeply nested logic can use these values. + */ + + pzm->rcvlen = rcvlen; + pzm->rcvndx = 0; + + /* Process each byte until we reach the end of the buffer (or until the + * data is discarded. + */ + + while (pzm->rcvndx < pzm->rcvlen) + { + /* Get the next byte from the buffer */ + + ch = pzm->rcvbuf[pzm->rcvndx]; + pzm->rcvndx++; + + /* Handle sequences of CAN characters. When we encounter 5 in a row, + * then we consider this a request to cancel the file transfer. + */ + + if (ch == ASCII_CAN) + { + if (++pzm->ncan >= 5) + { + zmdbg("Remote end has cancelled"); + pzm->rcvlen = 0; + pzm->rcvndx = 0; + return -EAGAIN; + } + } + else + { + /* Not CAN... reset the sequence count */ + + pzm->ncan = 0; + } + + /* Skip over XON and XOFF */ + + if (ch != ASCII_XON && ch != ASCII_XOFF) + { + /* And process what follows based on the current parsing state */ + + switch (pzm->pstate) + { + case PSTATE_IDLE: + ret = zm_idle(pzm, ch); + break; + + case PSTATE_HEADER: + ret = zm_header(pzm, ch); + break; + + case PSTATE_DATA: + ret = zm_data(pzm, ch); + break; + + case PSTATE_FINISH: + ret = zm_finish(pzm, ch); + break; + + /* This should not happen */ + + default: + zmdbg("ERROR: Invalid state: %d\n", pzm->pstate); + ret = -EINVAL; + break; + } + + /* Handle end-of-transfer and irrecoverable errors by breaking out + * of the loop and return a non-zero return value to indicate that + * transfer is complete. + */ + + if (ret != OK) + { + zmdbg("Aborting: %d\n", ret); + return ret; + } + } + } + + /* If we made it through the entire buffer with no errors detected, then + * return OK == 0 meaning that everything is okay, but we are not finished + * with the transfer. + */ + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: zm_datapump + * + * Description: + * Drive the Zmodem state machine by reading data from the remote peer and + * providing that data to the parser. This loop runs until a fatal error + * is detected or until the state machine reports that the transfer has + * completed successfully. + * + ****************************************************************************/ + +int zm_datapump(FAR struct zm_state_s *pzm) +{ + int ret = OK; + ssize_t nread; + + /* Loop until either a read error occurs or until a non-zero value is + * returned by the parser. + */ + + do + { + /* Start/restart the timer. Whenever we read data from the peer we + * must anticipate a timeout because we can never be sure that the peer + * is still responding. + */ + + sched_lock(); + zm_timerstart(pzm, pzm->timeout); + + /* Read a block of data. read() will return: (1) nread > 0 and nread + * <= CONFIG_SYSTEM_ZMODEM_RCVBUFSIZE on success, (2) nread == 0 on end + * of file, or (3) nread < 0 on a read error or interruption by a + * signal. + */ + + nread = read(pzm->remfd, pzm->rcvbuf, CONFIG_SYSTEM_ZMODEM_RCVBUFSIZE); + + /* Stop the timer */ + + (void)zm_timerstop(pzm); + sched_unlock(); + + /* EOF from the remote peer can only mean that we lost the connection + * somehow. + */ + + if (nread == 0) + { + zmdbg("ERROR: Unexpected end-of-file\n"); + return -ENOTCONN; + } + + /* Did some error occur? */ + + else if (nread < 0) + { + int errorcode = errno; + + /* EINTR is not an error... it simply means that this read was + * interrupted by an signal before it obtained in data. However, + * the signal may be SIGALRM indicating an timeout condition. + * We will know in this case because the signal handler will set + * ZM_FLAG_TIMEOUT. + */ + + if (errorcode == EINTR) + { + /* Check for a timeout */ + + if ((pzm->flags & ZM_FLAG_TIMEOUT) != 0) + { + /* Yes... a timeout occurred */ + + zm_timeout(pzm); + } + + /* No.. then just ignore the EINTR. */ + } + else + { + /* But anything else is bad and we will return the failure + * in those cases. + */ + + zmdbg("ERROR: read failed: %d\n", errorcode); + return -errorcode; + } + } + + /* Then provide that data to the state machine via zm_parse(). + * zm_parse() will return a non-zero value if we need to terminate + * the loop (with a negative value indicating a failure). + */ + + else /* nread > 0 */ + { + ret = zm_parse(pzm, nread); + if (ret < 0) + { + zmdbg("ERROR: zm_parse failed: %d\n", ret); + } + } + } + while (ret == OK); + + return ret; +} + + +/**************************************************************************** + * Name: zm_readstate + * + * Description: + * Enter PSTATE_DATA. + * + ****************************************************************************/ + +void zm_readstate(FAR struct zm_state_s *pzm) +{ + zmdbg("PSTATE %d:%d->%d.%d\n", + pzm->pstate, pzm->psubstate, PSTATE_DATA, PDATA_READ); + + pzm->pstate = PSTATE_DATA; + pzm->psubstate = PDATA_READ; + pzm->pktlen = 0; + pzm->ncrc = 0; +} + +/**************************************************************************** + * Name: zm_timeout + * + * Description: + * Called by the watchdog logic if/when a timeout is detected. + * + ****************************************************************************/ + +int zm_timeout(FAR struct zm_state_s *pzm) +{ + return zm_event(pzm, ZME_TIMEOUT); +} -- cgit v1.2.3