summaryrefslogtreecommitdiff
path: root/apps/netutils
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-11 18:47:04 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-11 18:47:04 -0600
commit4b160ee945b9dd9fed9d68950be36637b99c8769 (patch)
tree55322e2f0818bbdc82954164e33c263a9f046c4d /apps/netutils
parent5e174d14c12a6b1a40248de055b6ff1e66e755b1 (diff)
downloadpx4-nuttx-4b160ee945b9dd9fed9d68950be36637b99c8769.tar.gz
px4-nuttx-4b160ee945b9dd9fed9d68950be36637b99c8769.tar.bz2
px4-nuttx-4b160ee945b9dd9fed9d68950be36637b99c8769.zip
Bringing PPPD yet closer to the NuttX coding style
Diffstat (limited to 'apps/netutils')
-rw-r--r--apps/netutils/pppd/ahdlc.c62
-rw-r--r--apps/netutils/pppd/chat.c20
-rw-r--r--apps/netutils/pppd/ipcp.c141
-rw-r--r--apps/netutils/pppd/lcp.c33
-rw-r--r--apps/netutils/pppd/pap.c26
-rw-r--r--apps/netutils/pppd/ppp.c62
6 files changed, 200 insertions, 144 deletions
diff --git a/apps/netutils/pppd/ahdlc.c b/apps/netutils/pppd/ahdlc.c
index 29287f89d..de593a8bb 100644
--- a/apps/netutils/pppd/ahdlc.c
+++ b/apps/netutils/pppd/ahdlc.c
@@ -57,9 +57,7 @@
# undef PACKET_TX_DEBUG
#endif
-/*---------------------------------------------------------------------------
- * ahdlc flags bit defins, for ahdlc_flags variable
- ---------------------------------------------------------------------------*/
+/* ahdlc flags bit defins, for ahdlc_flags variable */
/* Escaped mode bit */
@@ -77,8 +75,9 @@
* Private Functions
****************************************************************************/
-/*---------------------------------------------------------------------------*/
-/* Simple and fast CRC16 routine for embedded processors.
+/****************************************************************************
+ * Simple and fast CRC16 routine for embedded processors.
+ *
* Just slightly slower than the table lookup method but consumes
* almost no space. Much faster and smaller than the loop and
* shift method that is widely used in the embedded space.
@@ -87,8 +86,8 @@
* data = (crcvalue ^ inputchar) & 0xff;
* data = (data ^ (data << 4)) & 0xff;
* crc = (crc >> 8) ^ ((data << 8) ^ (data <<3) ^ (data >> 4))
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
static u16_t crcadd(u16_t crcvalue, u8_t c)
{
@@ -101,11 +100,15 @@ static u16_t crcadd(u16_t crcvalue, u8_t c)
return ((crcvalue >> 8) ^ b);
}
-/*---------------------------------------------------------------------------*/
-/* ahdlc_init(buffer, buffersize) - this initializes the ahdlc engine to
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * ahdlc_init(buffer, buffersize) - this initializes the ahdlc engine to
* allow for rx frames.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void ahdlc_init(struct ppp_context_s *ctx)
{
@@ -118,11 +121,11 @@ void ahdlc_init(struct ppp_context_s *ctx)
#endif
}
-/*---------------------------------------------------------------------------*/
-/* ahdlc_rx_ready() - resets the ahdlc engine to the beginning of frame
+/****************************************************************************
+ * ahdlc_rx_ready() - resets the ahdlc engine to the beginning of frame
* state.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void ahdlc_rx_ready(struct ppp_context_s *ctx)
{
@@ -131,15 +134,15 @@ void ahdlc_rx_ready(struct ppp_context_s *ctx)
ctx->ahdlc_flags |= AHDLC_RX_READY;
}
-/*---------------------------------------------------------------------------*/
-/* ahdlc receive function - This routine processes incoming bytes and tries
+/****************************************************************************
+ * ahdlc receive function - This routine processes incoming bytes and tries
* to build a PPP frame.
*
* Two possible reasons that ahdlc_rx will not process characters:
* o Buffer is locked - in this case ahdlc_rx returns 1, char
* sending routing should retry.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
u8_t ahdlc_rx(struct ppp_context_s *ctx, u8_t c)
{
@@ -299,14 +302,14 @@ u8_t ahdlc_rx(struct ppp_context_s *ctx, u8_t c)
return 0;
}
-/*---------------------------------------------------------------------------*/
-/* ahdlc_tx_char(char) - write a character to the serial device,
+/****************************************************************************
+ * ahdlc_tx_char(char) - write a character to the serial device,
* escape if necessary.
*
- * Relies on local global vars : ahdlc_tx_crc, ahdlc_flags.
+ * Relies on local global vars : ahdlc_tx_crc, ahdlc_flags.
* Modifies local global vars : ahdlc_tx_crc.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void ahdlc_tx_char(struct ppp_context_s *ctx, u16_t protocol, u8_t c)
{
@@ -332,15 +335,16 @@ void ahdlc_tx_char(struct ppp_context_s *ctx, u16_t protocol, u8_t c)
ppp_arch_putchar(ctx, c);
}
-/*---------------------------------------------------------------------------*/
-/* ahdlc_tx(protocol,buffer,len) - Transmit a PPP frame.
+/****************************************************************************
+ * ahdlc_tx(protocol,buffer,len) - Transmit a PPP frame.
+ *
* Buffer contains protocol data, ahdlc_tx addes address, control and
* protocol data.
*
* Relies on local global vars : ahdlc_tx_crc, ahdlc_flags.
* Modifies local global vars : ahdlc_tx_crc.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
u8_t ahdlc_tx(struct ppp_context_s *ctx, u16_t protocol, u8_t *header,
u8_t *buffer, u16_t headerlen, u16_t datalen)
@@ -443,5 +447,3 @@ u8_t ahdlc_tx(struct ppp_context_s *ctx, u16_t protocol, u8_t *header,
O
return 0;
}
-
-/*---------------------------------------------------------------------------*/
diff --git a/apps/netutils/pppd/chat.c b/apps/netutils/pppd/chat.c
index ce900f478..e3120f647 100644
--- a/apps/netutils/pppd/chat.c
+++ b/apps/netutils/pppd/chat.c
@@ -54,6 +54,10 @@
* Private Functions
****************************************************************************/
+/****************************************************************************
+ * Name: chat_read_byte
+ ****************************************************************************/
+
static int chat_read_byte(int fd, char* c, int timeout)
{
int ret;
@@ -80,12 +84,20 @@ static int chat_read_byte(int fd, char* c, int timeout)
return 0;
}
+/****************************************************************************
+ * Name: chat_flush
+ ****************************************************************************/
+
static void chat_flush(int fd)
{
char tmp;
while (chat_read_byte(fd, &tmp, 0) == 0);
}
+/****************************************************************************
+ * Name: chat_check_response
+ ****************************************************************************/
+
static int chat_check_response(int fd, const char* response, int timeout)
{
char c;
@@ -119,6 +131,14 @@ static int chat_check_response(int fd, const char* response, int timeout)
return 0;
}
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: ppp_chat
+ ****************************************************************************/
+
int ppp_chat(int fd, struct chat_script_s *script, int echo)
{
int ret;
diff --git a/apps/netutils/pppd/ipcp.c b/apps/netutils/pppd/ipcp.c
index 4dd695f4a..16133bd88 100644
--- a/apps/netutils/pppd/ipcp.c
+++ b/apps/netutils/pppd/ipcp.c
@@ -76,7 +76,13 @@ static const u8_t ipcplist[] =
* Private Functions
****************************************************************************/
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: printip
+ ****************************************************************************/
#if 0
void printip(uip_ipaddr_t ip2)
@@ -88,7 +94,9 @@ void printip(uip_ipaddr_t ip2)
# define printip(x)
#endif
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: ipcp_init
+ ****************************************************************************/
void ipcp_init(struct ppp_context_s *ctx)
{
@@ -110,8 +118,13 @@ void ipcp_init(struct ppp_context_s *ctx)
#endif
}
-/*---------------------------------------------------------------------------*/
-/* IPCP RX protocol Handler */
+/****************************************************************************
+ * Name: ipcp_rx
+ *
+ * Description:
+ * IPCP RX protocol Handler
+ *
+ ****************************************************************************/
void ipcp_rx(struct ppp_context_s *ctx, u8_t *buffer, u16_t count)
{
@@ -412,7 +425,9 @@ void ipcp_rx(struct ppp_context_s *ctx, u8_t *buffer, u16_t count)
}
}
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: ipcp_task
+ ****************************************************************************/
void ipcp_task(struct ppp_context_s *ctx, u8_t *buffer)
{
@@ -424,88 +439,86 @@ void ipcp_task(struct ppp_context_s *ctx, u8_t *buffer)
send a request */
if (!(ctx->ipcp_state & IPCP_TX_UP) && !(ctx->ipcp_state & IPCP_TX_TIMEOUT))
- {
- /* Check if we have a request pending */
+ {
+ /* Check if we have a request pending */
- if ((ppp_arch_clock_seconds() - ctx->ipcp_prev_seconds) > IPCP_TIMEOUT)
- {
- ctx->ipcp_prev_seconds = ppp_arch_clock_seconds();
+ if ((ppp_arch_clock_seconds() - ctx->ipcp_prev_seconds) > IPCP_TIMEOUT)
+ {
+ ctx->ipcp_prev_seconds = ppp_arch_clock_seconds();
- /* No pending request, lets build one */
+ /* No pending request, lets build one */
- pkt=(IPCPPKT *)buffer;
+ pkt=(IPCPPKT *)buffer;
- /* Configure-Request only here, write id */
+ /* Configure-Request only here, write id */
- pkt->code = CONF_REQ;
- pkt->id = ctx->ppp_id;
+ pkt->code = CONF_REQ;
+ pkt->id = ctx->ppp_id;
- bptr = pkt->data;
+ bptr = pkt->data;
- /* Write options, we want IP address, and DNS addresses if set. */
- /* Write zeros for IP address the first time */
+ /* Write options, we want IP address, and DNS addresses if set. */
+ /* Write zeros for IP address the first time */
- *bptr++ = IPCP_IPADDRESS;
- *bptr++ = 0x6;
- *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[0];
- *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[1];
- *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[2];
- *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[3];
+ *bptr++ = IPCP_IPADDRESS;
+ *bptr++ = 0x6;
+ *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[0];
+ *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[1];
+ *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[2];
+ *bptr++ = (u8_t)((u8_t*)&ctx->local_ip)[3];
#ifdef IPCP_GET_PRI_DNS
- if (!(ppp_ipcp_state & IPCP_PRI_DNS_BIT))
- {
- /* Write zeros for IP address the first time */
-
- *bptr++ = IPCP_PRIMARY_DNS;
- *bptr++ = 0x6;
- *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[0];
- *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[1];
- *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[2];
- *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[3];
- }
+ if (!(ppp_ipcp_state & IPCP_PRI_DNS_BIT))
+ {
+ /* Write zeros for IP address the first time */
+
+ *bptr++ = IPCP_PRIMARY_DNS;
+ *bptr++ = 0x6;
+ *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[0];
+ *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[1];
+ *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[2];
+ *bptr++ = ((u8_t*)&ctx->pri_dns_addr)[3];
+ }
#endif
#ifdef IPCP_GET_SEC_DNS
- if (!(ppp_ipcp_state & IPCP_SEC_DNS_BIT))
- {
- /* Write zeros for IP address the first time */
-
- *bptr++ = IPCP_SECONDARY_DNS;
- *bptr++ = 0x6;
- *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[0];
- *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[1];
- *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[2];
- *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[3];
- }
+ if (!(ppp_ipcp_state & IPCP_SEC_DNS_BIT))
+ {
+ /* Write zeros for IP address the first time */
+
+ *bptr++ = IPCP_SECONDARY_DNS;
+ *bptr++ = 0x6;
+ *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[0];
+ *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[1];
+ *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[2];
+ *bptr++ = ((u8_t*)&ctx->sec_dns_addr)[3];
+ }
#endif
- /* Write length */
+ /* Write length */
- t = bptr - buffer;
+ t = bptr - buffer;
- /* length here - code and ID + */
+ /* length here - code and ID + */
- pkt->len = htons(t);
+ pkt->len = htons(t);
- DEBUG1(("\n**Sending IPCP Request packet\n"));
+ DEBUG1(("\n**Sending IPCP Request packet\n"));
- /* Send packet ahdlc_txz(procol,header,data,headerlen,datalen); */
+ /* Send packet ahdlc_txz(procol,header,data,headerlen,datalen); */
- ahdlc_tx(ctx, IPCP, 0, buffer, 0, t);
+ ahdlc_tx(ctx, IPCP, 0, buffer, 0, t);
- /* Inc retry */
+ /* Inc retry */
- ctx->ipcp_retry++;
+ ctx->ipcp_retry++;
- /* Have we timed out? (combine the timers?) */
+ /* Have we timed out? (combine the timers?) */
- if (ctx->ipcp_retry > IPCP_RETRY_COUNT)
- {
- ctx->ipcp_state &= IPCP_TX_TIMEOUT;
- }
- }
- }
+ if (ctx->ipcp_retry > IPCP_RETRY_COUNT)
+ {
+ ctx->ipcp_state &= IPCP_TX_TIMEOUT;
+ }
+ }
+ }
}
-
-/*---------------------------------------------------------------------------*/
diff --git a/apps/netutils/pppd/lcp.c b/apps/netutils/pppd/lcp.c
index e267abc14..cd4d8850a 100644
--- a/apps/netutils/pppd/lcp.c
+++ b/apps/netutils/pppd/lcp.c
@@ -84,9 +84,10 @@ static const u8_t lcplist[] =
* Private Functions
****************************************************************************/
-/*---------------------------------------------------------------------------*/
-/* lcp_init() - Initialize the LCP engine to startup values */
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * lcp_init() - Initialize the LCP engine to startup values
+ *
+ ****************************************************************************/
void lcp_init(struct ppp_context_s *ctx)
{
@@ -94,13 +95,13 @@ void lcp_init(struct ppp_context_s *ctx)
ctx->lcp_retry = 0;
}
-/*---------------------------------------------------------------------------*/
-/* lcp_rx() - Receive an LCP packet and process it.
+/****************************************************************************
+ * lcp_rx() - Receive an LCP packet and process it.
* This routine receives a LCP packet in buffer of length count.
* Process it here, support for CONF_REQ, CONF_ACK, CONF_NACK, CONF_REJ or
* TERM_REQ.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void lcp_rx(struct ppp_context_s *ctx, u8_t *buffer, u16_t count)
{
@@ -403,7 +404,9 @@ void lcp_rx(struct ppp_context_s *ctx, u8_t *buffer, u16_t count)
}
}
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: lcp_disconnect
+ ****************************************************************************/
void lcp_disconnect(struct ppp_context_s *ctx, u8_t id)
{
@@ -418,7 +421,9 @@ void lcp_disconnect(struct ppp_context_s *ctx, u8_t id)
ahdlc_tx(ctx, LCP, 0, buffer, 0, bptr - buffer);
}
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: lcp_echo_request
+ ****************************************************************************/
void lcp_echo_request(struct ppp_context_s *ctx, u8_t *buffer)
{
@@ -463,14 +468,14 @@ void lcp_echo_request(struct ppp_context_s *ctx, u8_t *buffer)
}
}
-/*---------------------------------------------------------------------------*/
-/* lcp_task(buffer) - This routine see if a lcp request needs to be sent
+/****************************************************************************
+ * lcp_task(buffer) - This routine see if a lcp request needs to be sent
* out. It uses the passed buffer to form the packet. This formed LCP
* request is what we negotiate for sending options on the link.
*
* Currently we negotiate : Magic Number Only, but this will change.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void lcp_task(struct ppp_context_s *ctx, u8_t *buffer)
{
@@ -591,5 +596,3 @@ void lcp_task(struct ppp_context_s *ctx, u8_t *buffer)
}
}
}
-
-/*---------------------------------------------------------------------------*/
diff --git a/apps/netutils/pppd/pap.c b/apps/netutils/pppd/pap.c
index 7e732f2b1..1e5363aa4 100644
--- a/apps/netutils/pppd/pap.c
+++ b/apps/netutils/pppd/pap.c
@@ -62,7 +62,13 @@
* Private Functions
****************************************************************************/
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pap_init
+ ****************************************************************************/
void pap_init(struct ppp_context_s *ctx)
{
@@ -71,9 +77,10 @@ void pap_init(struct ppp_context_s *ctx)
ctx->pap_prev_seconds = 0;
}
-/*---------------------------------------------------------------------------*/
-/* pap_rx() - PAP RX protocol Handler */
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * pap_rx() - PAP RX protocol Handler
+ *
+ ****************************************************************************/
void pap_rx(struct ppp_context_s *ctx, u8_t *buffer, u16_t count)
{
@@ -109,11 +116,12 @@ void pap_rx(struct ppp_context_s *ctx, u8_t *buffer, u16_t count)
break;
}
}
-/*---------------------------------------------------------------------------*/
-/* pap_task() - This task needs to be called every so often during the PAP
+
+/****************************************************************************
+ * pap_task() - This task needs to be called every so often during the PAP
* negotiation phase. This task sends PAP REQ packets.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void pap_task(struct ppp_context_s *ctx, u8_t *buffer)
{
@@ -185,5 +193,3 @@ void pap_task(struct ppp_context_s *ctx, u8_t *buffer)
}
}
}
-
-/*---------------------------------------------------------------------------*/
diff --git a/apps/netutils/pppd/ppp.c b/apps/netutils/pppd/ppp.c
index 961d72151..8eaa2d6e4 100644
--- a/apps/netutils/pppd/ppp.c
+++ b/apps/netutils/pppd/ppp.c
@@ -67,8 +67,10 @@
* Private Functions
****************************************************************************/
-/*---------------------------------------------------------------------------*/
-/* Unknown Protocol Handler, sends reject */
+/****************************************************************************
+ * Unknown Protocol Handler, sends reject
+ *
+ ****************************************************************************/
static void ppp_reject_protocol(struct ppp_context_s *ctx, u16_t protocol,
u8_t *buffer, u16_t count)
@@ -106,7 +108,13 @@ static void ppp_reject_protocol(struct ppp_context_s *ctx, u16_t protocol,
ahdlc_tx(ctx, LCP, buffer, 0, (u16_t)(count + 6), 0);
}
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: dump_ppp_packet
+ ****************************************************************************/
#if PACKET_RX_DEBUG
void dump_ppp_packet(u8_t *buffer, u16_t len)
@@ -128,11 +136,11 @@ void dump_ppp_packet(u8_t *buffer, u16_t len)
}
#endif
-/*---------------------------------------------------------------------------*/
-/* Initialize and start PPP engine. This just sets things up to
+/****************************************************************************
+ * Initialize and start PPP engine. This just sets things up to
* starting values. This can stay a private method.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void ppp_init(struct ppp_context_s *ctx)
{
@@ -151,18 +159,17 @@ void ppp_init(struct ppp_context_s *ctx)
ahdlc_rx_ready(ctx);
}
-/*---------------------------------------------------------------------------*/
-/* raise_ppp() - This routine will try to bring up a PPP connection,
+/****************************************************************************
+ * raise_ppp() - This routine will try to bring up a PPP connection,
* It is blocking. In the future we probably want to pass a
* structure with all the options on bringing up a PPP link, like
* server/client, DSN server, username password for PAP... +++ for
* now just use config and bit defines
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
#if 0
-u16_t
-ppp_raise(u8_t config, u8_t *username, u8_t *password)
+u16_t ppp_raise(u8_t config, u8_t *username, u8_t *password)
{
u16_t status = 0;
@@ -223,7 +230,9 @@ ppp_raise(u8_t config, u8_t *username, u8_t *password)
}
#endif
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: ppp_connect
+ ****************************************************************************/
void ppp_connect(struct ppp_context_s *ctx)
{
@@ -239,7 +248,9 @@ void ppp_connect(struct ppp_context_s *ctx)
ctx->ppp_flags = PPP_RX_READY;
}
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: ppp_send
+ ****************************************************************************/
void ppp_send(struct ppp_context_s *ctx)
{
@@ -251,7 +262,9 @@ void ppp_send(struct ppp_context_s *ctx)
}
}
-/*---------------------------------------------------------------------------*/
+/****************************************************************************
+ * Name: ppp_poll
+ ****************************************************************************/
void ppp_poll(struct ppp_context_s *ctx)
{
@@ -305,11 +318,11 @@ void ppp_poll(struct ppp_context_s *ctx)
}
}
-/*---------------------------------------------------------------------------*/
-/* ppp_upcall() - this is where valid PPP frames from the ahdlc layer are
+/****************************************************************************
+ * ppp_upcall() - this is where valid PPP frames from the ahdlc layer are
* sent to be processed and demuxed.
- */
-/*---------------------------------------------------------------------------*/
+ *
+ ****************************************************************************/
void ppp_upcall(struct ppp_context_s *ctx, u16_t protocol, u8_t *buffer, u16_t len)
{
@@ -364,13 +377,14 @@ void ppp_upcall(struct ppp_context_s *ctx, u16_t protocol, u8_t *buffer, u16_t l
}
}
-/*---------------------------------------------------------------------------*/
-/* scan_packet(list,buffer,len)
+/****************************************************************************
+ * scan_packet(list,buffer,len)
*
* list = list of supported ID's
* *buffer pointer to the first code in the packet
* length of the codespace
- */
+ *
+ ****************************************************************************/
u16_t scan_packet(struct ppp_context_s *ctx, u16_t protocol, const u8_t *list,
u8_t *buffer, u8_t *options, u16_t len)
@@ -450,5 +464,3 @@ u16_t scan_packet(struct ppp_context_s *ctx, u16_t protocol, const u8_t *list,
return bad;
}
-
-/*---------------------------------------------------------------------------*/