summaryrefslogtreecommitdiff
path: root/nuttx/net/uip/uip_icmpping.c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-15 14:53:45 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-15 14:53:45 +0000
commit4146e9258e38aff358710951df827ab1eb63310d (patch)
tree3f9ac9233c65e3c5bfe8cdfbbac958e04680543b /nuttx/net/uip/uip_icmpping.c
parent329bf67f0c4b6beb77e5856c8038a3202909be58 (diff)
downloadpx4-nuttx-4146e9258e38aff358710951df827ab1eb63310d.tar.gz
px4-nuttx-4146e9258e38aff358710951df827ab1eb63310d.tar.bz2
px4-nuttx-4146e9258e38aff358710951df827ab1eb63310d.zip
Changing NuttX fixed size type names to C99 standard names -- things will be broken for awhile
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2344 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net/uip/uip_icmpping.c')
-rw-r--r--nuttx/net/uip/uip_icmpping.c31
1 files changed, 17 insertions, 14 deletions
diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c
index c1af6b5d1..b235edf09 100644
--- a/nuttx/net/uip/uip_icmpping.c
+++ b/nuttx/net/uip/uip_icmpping.c
@@ -42,6 +42,8 @@
defined(CONFIG_NET_ICMP_PING) && !defined(CONFIG_DISABLE_CLOCK)
#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <semaphore.h>
#include <debug.h>
@@ -55,7 +57,7 @@
#include "../net_internal.h" /* Should not include this! */
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
@@ -75,14 +77,14 @@ struct icmp_ping_s
FAR struct uip_callback_s *png_cb; /* Reference to callback instance */
sem_t png_sem; /* Use to manage the wait for the response */
- uint32 png_time; /* Start time for determining timeouts */
- uint32 png_ticks; /* System clock ticks to wait */
+ uint32_t png_time; /* Start time for determining timeouts */
+ uint32_t png_ticks; /* System clock ticks to wait */
int png_result; /* 0: success; <0:negated errno on fail */
uip_ipaddr_t png_addr; /* The peer to be ping'ed */
- uint16 png_id; /* Used to match requests with replies */
- uint16 png_seqno; /* IN: seqno to send; OUT: seqno recieved */
- uint16 png_datlen; /* The length of data to send in the ECHO request */
- boolean png_sent; /* TRUE... the PING request has been sent */
+ uint16_t png_id; /* Used to match requests with replies */
+ uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
+ uint16_t png_datlen; /* The length of data to send in the ECHO request */
+ bool png_sent; /* true... the PING request has been sent */
};
/****************************************************************************
@@ -116,7 +118,7 @@ struct icmp_ping_s
static inline int ping_timeout(struct icmp_ping_s *pstate)
{
- uint32 elapsed = g_system_timer - pstate->png_time;
+ uint32_t elapsed = g_system_timer - pstate->png_time;
if (elapsed >= pstate->png_ticks)
{
return TRUE;
@@ -145,11 +147,11 @@ static inline int ping_timeout(struct icmp_ping_s *pstate)
*
****************************************************************************/
-static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
- void *pvpriv, uint16 flags)
+static uint16_t ping_interrupt(struct uip_driver_s *dev, void *conn,
+ void *pvpriv, uint16_t flags)
{
struct icmp_ping_s *pstate = (struct icmp_ping_s *)pvpriv;
- ubyte *ptr;
+ uint8_t *ptr;
int failcode = -ETIMEDOUT;
int i;
@@ -243,7 +245,7 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno);
dev->d_sndlen= pstate->png_datlen + 4;
uip_icmpsend(dev, &pstate->png_addr);
- pstate->png_sent = TRUE;
+ pstate->png_sent = true;
return flags;
}
}
@@ -309,7 +311,8 @@ end_wait:
*
****************************************************************************/
-int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dsecs)
+int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno,
+ uint16_t datalen, int dsecs)
{
struct icmp_ping_s state;
irqstate_t save;
@@ -323,7 +326,7 @@ int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dse
state.png_id = id; /* The ID to use in the ECHO request */
state.png_seqno = seqno; /* The seqno to use int the ECHO request */
state.png_datlen = datalen; /* The length of data to send in the ECHO request */
- state.png_sent = FALSE; /* ECHO request not yet sent */
+ state.png_sent = false; /* ECHO request not yet sent */
save = irqsave();
state.png_time = g_system_timer;