summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/sim/src/up_devconsole.c4
-rw-r--r--nuttx/arch/sim/src/up_tapdev.c22
-rw-r--r--nuttx/examples/uip/main.c34
-rw-r--r--nuttx/include/net/uip/smtp.h61
-rw-r--r--nuttx/netutils/smtp/Make.defs5
-rw-r--r--nuttx/netutils/smtp/smtp.c360
6 files changed, 271 insertions, 215 deletions
diff --git a/nuttx/arch/sim/src/up_devconsole.c b/nuttx/arch/sim/src/up_devconsole.c
index 601a13bf3..31c4e46c6 100644
--- a/nuttx/arch/sim/src/up_devconsole.c
+++ b/nuttx/arch/sim/src/up_devconsole.c
@@ -33,6 +33,10 @@
*
************************************************************/
+#ifndef linux
+# error "Sorry, this will only work with Linux"
+#endif
+
/************************************************************
* Included Files
************************************************************/
diff --git a/nuttx/arch/sim/src/up_tapdev.c b/nuttx/arch/sim/src/up_tapdev.c
index 539667e6d..dd7cbde2c 100644
--- a/nuttx/arch/sim/src/up_tapdev.c
+++ b/nuttx/arch/sim/src/up_tapdev.c
@@ -38,6 +38,10 @@
*
****************************************************************************/
+#ifndef linux
+# error "Sorry, this will only work with Linux"
+#endif
+
/****************************************************************************
* Included Files
****************************************************************************/
@@ -55,20 +59,8 @@
#include <unistd.h>
#include <string.h>
-#if 0
-#include "uip/uip.h"
-#include <net/uip/uip-arch.h>
-#include <net/uip/uip-arp.h>
-#endif
-
-#ifdef linux
-# include <sys/ioctl.h>
-# include <linux/if.h>
-# include <linux/if_tun.h>
-# define DEVTAP "/dev/net/tun"
-#else /* linux */
-# define DEVTAP "/dev/tap0"
-#endif /* linux */
+#include <linux/if.h>
+#include <linux/if_tun.h>
extern int lib_rawprintf(const char *format, ...);
@@ -78,6 +70,8 @@ extern int lib_rawprintf(const char *format, ...);
#define TAPDEV_DEBUG 1
+#define DEVTAP "/dev/net/tun"
+
#define UIP_DRIPADDR0 192
#define UIP_DRIPADDR1 168
#define UIP_DRIPADDR2 0
diff --git a/nuttx/examples/uip/main.c b/nuttx/examples/uip/main.c
index 1c3fff340..1f88936a6 100644
--- a/nuttx/examples/uip/main.c
+++ b/nuttx/examples/uip/main.c
@@ -31,7 +31,7 @@
*
* This file is part of the uIP TCP/IP stack.
*
- * $Id: main.c,v 1.1.1.1 2007-08-26 23:10:37 patacongo Exp $
+ * $Id: main.c,v 1.2 2007-08-30 23:57:58 patacongo Exp $
*
*/
@@ -66,14 +66,17 @@ int user_start(int argc, char *argv[])
int i;
uip_ipaddr_t ipaddr;
#if defined(CONFIG_EXAMPLE_UIP_DHCPC)
- uint16 mac[6] = {1,2,3,4,5,6};
+ uint16 mac[6] = {1, 2, 3, 4, 5, 6};
+#endif
+#ifdef CONFIG_EXAMPLE_UIP_SMTP
+ void *handle;
#endif
- uip_ipaddr(ipaddr, 192,168,0,2);
+ uip_ipaddr(ipaddr, 192, 168, 0, 2);
uip_sethostaddr(ipaddr);
- uip_ipaddr(ipaddr, 192,168,0,1);
+ uip_ipaddr(ipaddr, 192, 168, 0, 1);
uip_setdraddr(ipaddr);
- uip_ipaddr(ipaddr, 255,255,255,0);
+ uip_ipaddr(ipaddr, 255, 255, 255, 0);
uip_setnetmask(ipaddr);
#if defined(CONFIG_EXAMPLE_UIP_WEBSERVER)
@@ -83,15 +86,19 @@ int user_start(int argc, char *argv[])
#elif defined(CONFIG_EXAMPLE_UIP_DHCPC)
dhcpc_init(&mac, 6);
#elif defined(CONFIG_EXAMPLE_UIP_SMTP)
- uip_ipaddr(ipaddr, 127,0,0,1);
- smtp_configure("localhost", ipaddr);
- SMTP_SEND("adam@sics.se", NULL, "uip-testing@example.com",
- "Testing SMTP from uIP",
- "Test message sent by uIP\r\n");
+ uip_ipaddr(ipaddr, 127, 0, 0, 1);
+ handle = smtp_init();
+ if (handle)
+ {
+ smtp_configure("localhost", ipaddr);
+ smtp_send("adam@sics.se", NULL, "uip-testing@example.com",
+ "Testing SMTP from uIP", "Test message sent by uIP\r\n");
+ smtp_close(handle);
+ }
#elif defined(CONFIG_EXAMPLE_UIP_WEBCLIENT)
webclient_init();
resolv_init();
- uip_ipaddr(ipaddr, 195,54,122,204);
+ uip_ipaddr(ipaddr, 195, 54, 122, 204);
resolv_conf(ipaddr);
resolv_query("www.sics.se");
#endif
@@ -134,11 +141,6 @@ void dhcpc_configured(const struct dhcpc_state *s)
}
#endif /* __DHCPC_H__ */
-void smtp_done(unsigned char code)
-{
- printf("SMTP done with code %d\n", code);
-}
-
void webclient_closed(void)
{
printf("Webclient: connection closed\n");
diff --git a/nuttx/include/net/uip/smtp.h b/nuttx/include/net/uip/smtp.h
index da2683f65..c90240d6d 100644
--- a/nuttx/include/net/uip/smtp.h
+++ b/nuttx/include/net/uip/smtp.h
@@ -1,9 +1,15 @@
+/****************************************************************************
/* smtp.h
* SMTP header file
- * Author: Adam Dunkels <adam@dunkels.com>
*
- * Copyright (c) 2002, Adam Dunkels.
- * All rights reserved.
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Heavily leveraged from uIP 1.0 which also has a BSD-like license:
+ *
+ * Author: Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2002, Adam Dunkels.
+ * All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -28,48 +34,31 @@
* 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.
- */
+ *
+ ****************************************************************************/
#ifndef __SMTP_H__
#define __SMTP_H__
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <sys/types.h>
#include <net/uip/uipopt.h>
-/* Error number that signifies a non-error condition. */
-
-#define SMTP_ERR_OK 0
-
-/* Callback function that is called when an e-mail transmission is
- * done.
- *
- * This function must be implemented by the module that uses the SMTP
- * module.
- *
- * error The number of the error if an error occured, or
- * SMTP_ERR_OK.
- */
-
-void smtp_done(unsigned char error);
-
-void smtp_init(void);
-void smtp_configure(char *localhostname, uint16 *smtpserver);
-unsigned char smtp_send(char *to, char *from,
- char *subject, char *msg,
- uint16 msglen);
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
-struct smtp_state
-{
- uint8 state;
- char *to;
- char *from;
- char *subject;
- char *msg;
- uint16 msglen;
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
- uint16 sentlen, textlen;
- uint16 sendptr;
-};
+extern void *smtp_open(void);
+extern void smtp_configure(void *handle, char *localhostname, void *smtpserver);
+extern int smtp_send(void *handle, char *to, char *cc, char *from, char *subject, char *msg, int msglen);
+extern void smtp_close(void *handle);
#endif /* __SMTP_H__ */
diff --git a/nuttx/netutils/smtp/Make.defs b/nuttx/netutils/smtp/Make.defs
index b749677c9..c055c543d 100644
--- a/nuttx/netutils/smtp/Make.defs
+++ b/nuttx/netutils/smtp/Make.defs
@@ -33,6 +33,5 @@
#
############################################################################
-# Does not build
-# SMTP_ASRCS =
-# SMTP_CSRCS = smtp.c smtp-strings.c
+SMTP_ASRCS =
+SMTP_CSRCS = smtp.c smtp-strings.c
diff --git a/nuttx/netutils/smtp/smtp.c b/nuttx/netutils/smtp/smtp.c
index 98dd468e3..d4d8feee0 100644
--- a/nuttx/netutils/smtp/smtp.c
+++ b/nuttx/netutils/smtp/smtp.c
@@ -1,6 +1,11 @@
-/* smtp.c
+/****************************************************************************
+ * smtp.c
* smtp SMTP E-mail sender
- * Author: Adam Dunkels <adam@dunkels.com>
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Heavily leveraged from uIP 1.0 which also has a BSD-like license:
*
* The Simple Mail Transfer Protocol (SMTP) as defined by RFC821 is
* the standard way of sending and transfering e-mail on the
@@ -8,8 +13,9 @@
* example of how to implement protocols in uIP, and is able to send
* out e-mail but has not been extensively tested.
*
- * Copyright (c) 2004, Adam Dunkels.
- * All rights reserved.
+ * Author: Adam Dunkels <adam@dunkels.com>
+ * Copyright (c) 2004, Adam Dunkels.
+ * All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,16 +40,16 @@
* 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.
- *
- * This file is part of the uIP TCP/IP stack.
- *
- * Author: Adam Dunkels <adam@sics.se>
- *
- * $Id: smtp.c,v 1.1.1.1 2007-08-26 23:07:06 patacongo Exp $
- */
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <sys/types.h>
#include <string.h>
+#include <stdlib.h>
+#include <semaphore.h>
#include <net/uip/uip.h>
#include <net/uip/psock.h>
@@ -51,10 +57,7 @@
#include "smtp-strings.h"
-static struct smtp_state s;
-
-static char *localhostname;
-static uip_ipaddr_t smtpserver;
+#define SMTP_INPUT_BUFFER_SIZE 512
#define ISO_nl 0x0a
#define ISO_cr 0x0d
@@ -66,110 +69,141 @@ static uip_ipaddr_t smtpserver;
#define ISO_4 0x34
#define ISO_5 0x35
+/* This structure represents the state of a single SMTP transaction */
-/*---------------------------------------------------------------------------*/
-static
-void smtp_thread(void)
+struct smtp_state
{
- psock_readto(&s.psock, ISO_nl);
+ uint8 state;
+ boolean connected;
+ sem_t sem;
+ struct psock psock;
+ uip_ipaddr_t smtpserver;
+ char *localhostname;
+ char *to;
+ char *cc;
+ char *from;
+ char *subject;
+ char *msg;
+ int msglen;
+ int sentlen;
+ int textlen;
+ int sendptr;
+ int result;
+ char buffer[SMTP_INPUT_BUFFER_SIZE];
+};
+
+static volatile struct smtp_state *gpsmtp = 0;
+
+static void smtp_send_message(struct smtp_state *psmtp)
+{
+ psock_readto(&psmtp->psock, ISO_nl);
- if(strncmp(s.inputbuffer, smtp_220, 3) != 0) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(2);
- pthread_exit(NULL);
- }
+ if (strncmp(psmtp->buffer, smtp_220, 3) != 0)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 2;
+ return;
+ }
- PSOCK_SEND_STR(&s.psock, (char *)smtp_helo);
- PSOCK_SEND_STR(&s.psock, localhostname);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_helo);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->localhostname);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- psock_readto(&s.psock, ISO_nl);
+ psock_readto(&psmtp->psock, ISO_nl);
- if(s.inputbuffer[0] != ISO_2) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(3);
- pthread_exit(NULL);
- }
+ if (psmtp->buffer[0] != ISO_2)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 3;
+ return;
+ }
- PSOCK_SEND_STR(&s.psock, (char *)smtp_mail_from);
- PSOCK_SEND_STR(&s.psock, s.from);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_mail_from);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->from);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- psock_readto(&s.psock, ISO_nl);
+ psock_readto(&psmtp->psock, ISO_nl);
- if(s.inputbuffer[0] != ISO_2) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(4);
- pthread_exit(NULL);
- }
+ if (psmtp->buffer[0] != ISO_2)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 3;
+ return;
+ }
- PSOCK_SEND_STR(&s.psock, (char *)smtp_rcpt_to);
- PSOCK_SEND_STR(&s.psock, s.to);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_rcpt_to);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->to);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- psock_readto(&s.psock, ISO_nl);
+ psock_readto(&psmtp->psock, ISO_nl);
- if(s.inputbuffer[0] != ISO_2) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(5);
- pthread_exit(NULL);
- }
+ if (psmtp->buffer[0] != ISO_2)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 5;
+ return;
+ }
- if(s.cc != 0) {
- PSOCK_SEND_STR(&s.psock, (char *)smtp_rcpt_to);
- PSOCK_SEND_STR(&s.psock, s.cc);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
+ if (psmtp->cc != 0)
+ {
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_rcpt_to);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->cc);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- psock_readto(&s.psock, ISO_nl);
+ psock_readto(&psmtp->psock, ISO_nl);
- if(s.inputbuffer[0] != ISO_2) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(6);
- pthread_exit(NULL);
+ if (psmtp->buffer[0] != ISO_2)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 6;
+ return;
+ }
}
- }
- PSOCK_SEND_STR(&s.psock, (char *)smtp_data);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_data);
+
+ psock_readto(&psmtp->psock, ISO_nl);
- psock_readto(&s.psock, ISO_nl);
+ if (psmtp->buffer[0] != ISO_3)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 7;
+ return;
+ }
- if(s.inputbuffer[0] != ISO_3) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(7);
- pthread_exit(NULL);
- }
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_to);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->to);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_to);
- PSOCK_SEND_STR(&s.psock, s.to);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
-
- if(s.cc != 0) {
- PSOCK_SEND_STR(&s.psock, (char *)smtp_cc);
- PSOCK_SEND_STR(&s.psock, s.cc);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
- }
+ if (psmtp->cc != 0)
+ {
+ PSOCK_SEND_STR(&psmtp->psock, (char *)psmtp->cc);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->cc);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
+ }
- PSOCK_SEND_STR(&s.psock, (char *)smtp_from);
- PSOCK_SEND_STR(&s.psock, s.from);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_from);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->from);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_subject);
- PSOCK_SEND_STR(&s.psock, s.subject);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnl);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_subject);
+ PSOCK_SEND_STR(&psmtp->psock, psmtp->subject);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnl);
- psock_send(&s.psock, s.msg, s.msglen);
+ psock_send(&psmtp->psock, psmtp->msg, psmtp->msglen);
- PSOCK_SEND_STR(&s.psock, (char *)smtp_crnlperiodcrnl);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_crnlperiodcrnl);
- psock_readto(&s.psock, ISO_nl);
- if(s.inputbuffer[0] != ISO_2) {
- PSOCK_CLOSE(&s.psock);
- smtp_done(8);
- pthread_exit(NULL);
- }
+ psock_readto(&psmtp->psock, ISO_nl);
+ if (psmtp->buffer[0] != ISO_2)
+ {
+ PSOCK_CLOSE(&psmtp->psock);
+ psmtp->result = 8;
+ return;
+ }
- PSOCK_SEND_STR(&s.psock, (char *)smtp_quit);
- smtp_done(SMTP_ERR_OK);
+ PSOCK_SEND_STR(&psmtp->psock, (char *)smtp_quit);
+ psmtp->result = 0;
}
/* This function is called by the UIP interrupt handling logic whenevent an
@@ -178,75 +212,109 @@ void smtp_thread(void)
void uip_interrupt_event(void)
{
- if(uip_closed()) {
- s.connected = 0;
- return;
- }
- if(uip_aborted() || uip_timedout()) {
- s.connected = 0;
- smtp_done(1);
- return;
- }
- smtp_thread();
+ if (gpsmtp)
+ {
+ if (uip_closed())
+ {
+ gpsmtp->connected = FALSE;
+ return;
+ }
+
+ if (uip_aborted() || uip_timedout())
+ {
+ gpsmtp->connected = FALSE;
+ }
+
+ sem_post((sem_t*)&gpsmtp->sem);
+ }
}
-/*---------------------------------------------------------------------------*/
-/**
- * Specificy an SMTP server and hostname.
+/* Specificy an SMTP server and hostname.
*
* This function is used to configure the SMTP module with an SMTP
* server and the hostname of the host.
*
- * \param lhostname The hostname of the uIP host.
+ * lhostname The hostname of the uIP host.
*
- * \param server A pointer to a 4-byte array representing the IP
+ * server A pointer to a 4-byte array representing the IP
* address of the SMTP server to be configured.
*/
-void
-smtp_configure(char *lhostname, void *server)
+
+void smtp_configure(void *handle, char *lhostname, void *server)
{
- localhostname = lhostname;
- uip_ipaddr_copy(smtpserver, server);
+ struct smtp_state *psmtp = (struct smtp_state *)handle;
+ psmtp->localhostname = lhostname;
+ uip_ipaddr_copy(psmtp->smtpserver, server);
}
-/*---------------------------------------------------------------------------*/
-/**
- * Send an e-mail.
+
+/* Send an e-mail.
*
- * \param to The e-mail address of the receiver of the e-mail.
- * \param cc The e-mail address of the CC: receivers of the e-mail.
- * \param from The e-mail address of the sender of the e-mail.
- * \param subject The subject of the e-mail.
- * \param msg The actual e-mail message.
- * \param msglen The length of the e-mail message.
+ * to The e-mail address of the receiver of the e-mail.
+ * cc The e-mail address of the CC: receivers of the e-mail.
+ * from The e-mail address of the sender of the e-mail.
+ * subject The subject of the e-mail.
+ * msg The actual e-mail message.
+ * msglen The length of the e-mail message.
*/
-unsigned char
-smtp_send(char *to, char *cc, char *from,
- char *subject, char *msg, uint16 msglen)
+
+int smtp_send(void *handle, char *to, char *cc, char *from, char *subject, char *msg, int msglen)
{
+ struct smtp_state *psmtp = (struct smtp_state *)handle;
struct uip_conn *conn;
- conn = uip_connect(smtpserver, HTONS(25));
- if(conn == NULL) {
- return 0;
- }
- s.connected = 1;
- s.to = to;
- s.cc = cc;
- s.from = from;
- s.subject = subject;
- s.msg = msg;
- s.msglen = msglen;
-
- psock_init(&s.psock, s.inputbuffer, sizeof(s.inputbuffer));
-
- return 1;
+ conn = uip_connect(&psmtp->smtpserver, HTONS(25));
+ if (conn == NULL)
+ {
+ return ERROR;
+ }
+
+ psmtp->connected = TRUE;
+ psmtp->to = to;
+ psmtp->cc = cc;
+ psmtp->from = from;
+ psmtp->subject = subject;
+ psmtp->msg = msg;
+ psmtp->msglen = msglen;
+ psmtp->result = OK;
+
+ gpsmtp = psmtp;
+ psock_init(&psmtp->psock, psmtp->buffer, SMTP_INPUT_BUFFER_SIZE);
+
+ /* And wait for the the socket to be connected */
+ sem_wait(&psmtp->sem);
+ gpsmtp = 0;
+
+ /* Was an error reported by interrupt handler? */
+ if (psmtp->result == OK )
+ {
+ /* No... Send the message */
+ smtp_send_message(psmtp);
+ }
+
+ return psmtp->result;
}
-/*---------------------------------------------------------------------------*/
-void
-smtp_init(void)
+
+void *smtp_open(void)
{
- s.connected = 0;
+ /* Allocate the handle */
+
+ struct smtp_state *psmtp = (struct smtp_state *)malloc(sizeof(struct smtp_state));
+ if (psmtp)
+ {
+ /* Initialize the handle */
+
+ memset(psmtp, 0, sizeof(struct smtp_state));
+ (void)sem_init(&psmtp->sem, 0, 0);
+ }
+ return (void*)psmtp;
}
-/*---------------------------------------------------------------------------*/
-/** @} */
-/** @} */
+
+void smtp_close(void *handle)
+{
+ struct smtp_state *psmtp = (struct smtp_state *)handle;
+ if (psmtp)
+ {
+ sem_destroy(&psmtp->sem);
+ free(psmtp);
+ }
+} \ No newline at end of file