From b2ef5f0d01a93f991267a9dbd58ec903319d96bf Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Thu, 10 Apr 2014 18:15:06 -0600 Subject: apps/netutils/ntpclient: Add a primitive NTP client. Initial checkin is untested and probably incomplete --- apps/netutils/Kconfig | 1 + apps/netutils/Make.defs | 4 + apps/netutils/README.txt | 2 + apps/netutils/ntpclient/.built | 0 apps/netutils/ntpclient/Kconfig | 35 +++ apps/netutils/ntpclient/Makefile | 100 ++++++++ apps/netutils/ntpclient/ntpclient.c | 482 ++++++++++++++++++++++++++++++++++++ apps/netutils/ntpclient/ntpv3.h | 207 ++++++++++++++++ 8 files changed, 831 insertions(+) create mode 100644 apps/netutils/ntpclient/.built create mode 100755 apps/netutils/ntpclient/Kconfig create mode 100755 apps/netutils/ntpclient/Makefile create mode 100644 apps/netutils/ntpclient/ntpclient.c create mode 100755 apps/netutils/ntpclient/ntpv3.h (limited to 'apps/netutils') diff --git a/apps/netutils/Kconfig b/apps/netutils/Kconfig index 42a6713a0..24573eef9 100644 --- a/apps/netutils/Kconfig +++ b/apps/netutils/Kconfig @@ -19,5 +19,6 @@ source "$APPSDIR/netutils/thttpd/Kconfig" source "$APPSDIR/netutils/uiplib/Kconfig" source "$APPSDIR/netutils/webclient/Kconfig" source "$APPSDIR/netutils/webserver/Kconfig" +source "$APPSDIR/netutils/ntpclient/Kconfig" source "$APPSDIR/netutils/discover/Kconfig" source "$APPSDIR/netutils/xmlrpc/Kconfig" diff --git a/apps/netutils/Make.defs b/apps/netutils/Make.defs index b603c9dd3..7e1d5eb1c 100644 --- a/apps/netutils/Make.defs +++ b/apps/netutils/Make.defs @@ -58,6 +58,10 @@ ifeq ($(CONFIG_NETUTILS_JSON),y) CONFIGURED_APPS += netutils/json endif +ifeq ($(CONFIG_NETUTILS_NTPCLIENT),y) +CONFIGURED_APPS += netutils/ntpclient +endif + ifeq ($(CONFIG_NETUTILS_RESOLV),y) CONFIGURED_APPS += netutils/resolv endif diff --git a/apps/netutils/README.txt b/apps/netutils/README.txt index 52becf800..5a58a45cf 100644 --- a/apps/netutils/README.txt +++ b/apps/netutils/README.txt @@ -65,6 +65,8 @@ highly influenced by uIP) include: information. ftpd - FTP server. See apps/include/netutils/ftpd.h for interface information. + ntpclient - This is a fragmentary NTP client. It neither well-tested + nor mature nor complete at this point in time. thttpd - This is a port of Jef Poskanzer's THTTPD HTPPD server. See http://acme.com/software/thttpd/ for general THTTPD information. See apps/include/netutils/thttpd.h diff --git a/apps/netutils/ntpclient/.built b/apps/netutils/ntpclient/.built new file mode 100644 index 000000000..e69de29bb diff --git a/apps/netutils/ntpclient/Kconfig b/apps/netutils/ntpclient/Kconfig new file mode 100755 index 000000000..fe0371197 --- /dev/null +++ b/apps/netutils/ntpclient/Kconfig @@ -0,0 +1,35 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config NETUTILS_NTPCLIENT + bool "NTP client" + default n + depends on NET_UDP + ---help--- + Enable support for the minimal NTP client. + +if NETUTILS_NTPCLIENT + +config NETUTILS_NTPCLIENT_SERVERIP + hex "NTP server IP address" + default 0x0a000001 + +config NETUTILS_NTPCLIENT_PORTNO + int "NTP server port number" + default 123 + +config NETUTILS_NTPCLIENT_STACKSIZE + int "NTP client daemon stack stack size" + default 2048 + +config NETUTILS_NTPCLIENT_SERVERPRIO + int "NTP client daemon priority" + default 100 + +config NETUTILS_NTPCLIENT_POLLDELAYSEC + int "NTP client poll interval (seconds)" + default 60 + +endif # NETUTILS_NTPCLIENT diff --git a/apps/netutils/ntpclient/Makefile b/apps/netutils/ntpclient/Makefile new file mode 100755 index 000000000..e3d0f5075 --- /dev/null +++ b/apps/netutils/ntpclient/Makefile @@ -0,0 +1,100 @@ +############################################################################ +# apps/netutils/ntpclient/Makefile +# +# Copyright (C) 2014 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +-include $(TOPDIR)/.config +-include $(TOPDIR)/Make.defs +include $(APPDIR)/Make.defs + +# NTP client daemon Library + +ASRCS = +CSRCS = + +ifeq ($(CONFIG_NET_UDP),y) +CSRCS += ntpclient.c +endif + +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ifeq ($(CONFIG_WINDOWS_NATIVE),y) + BIN = ..\..\libapps$(LIBEXT) +else +ifeq ($(WINTOOL),y) + BIN = ..\\..\\libapps$(LIBEXT) +else + BIN = ../../libapps$(LIBEXT) +endif +endif + +ROOTDEPPATH = --dep-path . + +# Common build + +VPATH = + +all: .built +.PHONY: context depend clean distclean + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +.built: $(OBJS) + $(call ARCHIVE, $(BIN), $(OBJS)) + $(Q) touch .built + +context: + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, .built) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/apps/netutils/ntpclient/ntpclient.c b/apps/netutils/ntpclient/ntpclient.c new file mode 100644 index 000000000..44d44557c --- /dev/null +++ b/apps/netutils/ntpclient/ntpclient.c @@ -0,0 +1,482 @@ +/**************************************************************************** + * netutils/ntpclient/ntpclient.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 "ntpv3.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* NTP Time is seconds since 1900. Convert to Unix time which is seconds + * since 1970 + */ + +#define NTP2UNIX_TRANLSLATION 2208988800u +#define NTP_VERSION 3 + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This enumeration describes the state of the NTP daemon */ + +enum ntpclient_daemon_e +{ + NTP_NOT_RUNNING = 0, + NTP_STARTED, + NTP_RUNNING, + NTP_STOP_REQUESTED, + NTP_STOPPED +}; + +/* This type describes the state of the NTP client daemon. Only once + * instance of the NTP daemon is permitted in this implementation. + */ + +struct ntpclient_daemon_s +{ + volatile uint8_t state; /* See enum ntpclient_daemon_e */ + sem_t interlock; /* Used to synchronize start and stop events */ + pid_t pid; /* Task ID of the NTP daemon */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* This type describes the state of the NTP client daemon. Only once + * instance of the NTP daemon is permitted in this implementation. This + * limitation is due only to this global data structure. + */ + +static struct ntpclient_daemon_s g_ntpclient_daemon; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Name: ntpclient_getuint32 + * + * Description: + * Return the big-endian, 4-byte value in network (big-endian) order. + * + ****************************************************************************/ + +static inline uint32_t ntpclient_getuint32(FAR uint8_t *ptr) +{ + /* Network order is big-endian; host order is irrelevant */ + + return (uint32_t)ptr[0] | /* LS byte appears first in data stream */ + ((uint32_t)ptr[1] << 8) | + ((uint32_t)ptr[2] << 16) | + ((uint32_t)ptr[3] << 24); +} + +/**************************************************************************** + * Name: ntpclient_settime + * + * Description: + * Given the NTP time in seconds, set the system time + * + ****************************************************************************/ + +static void ntpclient_settime(FAR uint8_t *timestamp) +{ + struct timespec tp; + time_t seconds; + uint32_t frac; + uint32_t nsec; +#ifdef CONFIG_HAVE_LONG_LONG + uint64_t tmp; +#else + uint32_t a16; + uint32_t b0; + uint32_t t32; + uint32_t t16; + uint32_t t0; +#endif + + /* NTP timestamps are represented as a 64-bit fixed-point number, in + * seconds relative to 0000 UT on 1 January 1900. The integer part is + * in the first 32 bits and the fraction part in the last 32 bits, as + * shown in the following diagram. + * + * 0 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | Integer Part | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | Fraction Part | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + */ + + seconds = ntpclient_getuint32(timestamp); + + /* Translate seconds to account for the difference in the origin time */ + + if (seconds > NTP2UNIX_TRANLSLATION) + { + seconds -= NTP2UNIX_TRANLSLATION; + } + + /* Conversion of the fractional part to nanoseconds: + * + * NSec = (f * 1,000,000,000) / 4,294,967,296 + * = (f * (5**9 * 2**9) / (2**32) + * = (f * 5**9) / (2**23) + * = (f * 1,953,125) / 8,388,608 + */ + + frac = ntpclient_getuint32(timestamp + 4); +#ifdef CONFIG_HAVE_LONG_LONG + /* if we have 64-bit long long values, then the computation is easy */ + + tmp = ((uint64_t)frac * 1953125) >> 23; + nsec = (uint32_t)tmp; + +#else + /* If we don't have 64 bit integer types, then the calculation is a little + * more complex: + * + * Let f = a << 16 + b + * 1,953,125 = 0x1d << 16 + 0xcd65 + * NSec << 23 = ((a << 16) + b) * ((0x1d << 16) + 0xcd65) + * = (a << 16) * 0x1d << 16) + + * (a << 16) * 0xcd65 + + * b * 0x1d << 16) + + * b * 0xcd65; + */ + + /* Break the fractional part up into two values */ + + a16 = frac >> 16; + b0 = frac & 0xffff; + + /* Get the b32 and b0 terms + * + * t32 = (a << 16) * 0x1d << 16) + * t0 = b * 0xcd65 + */ + + t32 = 0x001d * a16; + t0 = 0xcd65 * b0 + + /* Get the first b16 term + * + * (a << 16) * 0xcd65 + */ + + t16 = 0xcd65 * a16 + + /* Add the upper 16-bits to the b32 accumulator */ + + t32 += (t16 >> 16); + + /* Add the lower 16-bits to the b0 accumulator, handling carry to the b32 + * accumulator + */ + + t16 <<= 16; + if (t0 > (0xffffffff - t16)) + { + t32++; + } + else + { + t0 += t16; + } + + /* Get the second b16 term + * + * b * 0x1d << 16) + */ + + t16 = 0x001d * b + + /* Add the upper 16-bits to the b32 accumulator */ + + t32 += (t16 >> 16); + + /* Add the lower 16-bits to the b0 accumulator, handling carry to the b32 + * accumulator + */ + + t16 <<= 16; + if (t0 > (0xffffffff - t16)) + { + t32++; + } + else + { + t0 += t16; + } + + /* t32 and t0 represent the 64 bit product. Now shift right by 23 bits to + * accomplish the divide by by 2**23. + */ + + nsec = (t32 << (32 - 23)) + (t0 >> 23) +#endif + + /* Set the system time */ + + tp.tv_sec = seconds; + tp.tv_nsec = nsec; + clock_settime(CLOCK_REALTIME, &tp); + + svdbg("Set time to %ld seconds: %d\n", tp.tv_sec, ret); +} + +/**************************************************************************** + * Name: ntpclient_daemon + * + * Description: + * This the the NTP client daemon. This is a *very* minimal + * implementation! An NTP request is and the system clock is set when the + * response is received + * + ****************************************************************************/ + +static int ntpclient_daemon(int argc, char **argv) +{ + struct sockaddr_in server; + struct ntp_datagram_s xmit; + struct ntp_datagram_s recv; + struct timeval tv; + socklen_t socklen; + ssize_t nbytes; + int exitcode = EXIT_SUCCESS; + int ret; + int sd; + + /* Indicate that we have started */ + + g_ntpclient_daemon.state = NTP_RUNNING; + sem_post(&g_ntpclient_daemon.interlock); + + /* Create a datagram socket */ + + sd = socket(AF_INET, SOCK_DGRAM, 0); + if (sd < 0) + { + ndbg("ERROR: socket failed: %d\n", errno); + + g_ntpclient_daemon.state = NTP_STOPPED; + sem_post(&g_ntpclient_daemon.interlock); + return EXIT_FAILURE; + } + + /* Setup a receive timeout on the socket */ + + tv.tv_sec = 5; + tv.tv_usec = 0; + + ret = setsockopt(sd, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(struct timeval)); + if (ret < 0) + { + ndbg("ERROR: setsockopt failed: %d\n", errno); + + g_ntpclient_daemon.state = NTP_STOPPED; + sem_post(&g_ntpclient_daemon.interlock); + return EXIT_FAILURE; + } + + /* Setup or sockaddr_in struct with information about the server we are + * going to ask the the time from. + */ + + memset(&server, 0, sizeof(struct sockaddr_in)); + server.sin_family = AF_INET; + server.sin_port = htons(CONFIG_NETUTILS_NTPCLIENT_PORTNO); + server.sin_addr.s_addr = htonl(CONFIG_NETUTILS_NTPCLIENT_SERVERIP); + + /* Here we do the communication with the NTP server. This is a very simple + * client architecture. A request is sent and then a NTP packet is received. + * The NTP packet received is decoded to the recv structure for easy + * access. + */ + + while (g_ntpclient_daemon.state == NTP_STOP_REQUESTED) + { + memset(&xmit, 0, sizeof(xmit)); + xmit.lvm = MKLVM(0, 3, NTP_VERSION); + + svdbg("Sending a NTP packet\n"); + + ret = sendto(sd, &xmit, sizeof(struct ntp_datagram_s), + 0, (FAR struct sockaddr *)&server, + sizeof(struct sockaddr_in)); + if (ret < 0) + { + ndbg("ERROR: sendto() failed: %d\n", errno); + exitcode = EXIT_FAILURE; + break; + } + + /* Attempt to receive a packet (with a timeout) */ + + socklen = sizeof(struct sockaddr_in); + nbytes = recvfrom(sd, (void *)&recv, sizeof(struct ntp_datagram_s), + 0, (FAR struct sockaddr *)&server, &socklen); + if (nbytes >= NTP_DATAGRAM_MINSIZE) + { + svdbg("Setting time\n"); + ntpclient_settime(recv.recvtimestamp); + } + + /* A full implementation of an NTP client would requireq much more. I + * think we we can skip that here. + */ + + svdbg("Waiting for %d seconds\n", CONFIG_NETUTILS_NTPCLIENT_POLLDELAYSEC); + (void)sleep(CONFIG_NETUTILS_NTPCLIENT_POLLDELAYSEC); + } + + /* The NTP client is terminating */ + + g_ntpclient_daemon.state = NTP_STOPPED; + sem_post(&g_ntpclient_daemon.interlock); + return exitcode; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: ntpclient_start + * + * Description: + * Start the NTP daemon + * + ****************************************************************************/ + +int ntpclient_start(void) +{ + /* Is the NTP in a non-running state? */ + + sched_lock(); + if (g_ntpclient_daemon.state == NTP_NOT_RUNNING || + g_ntpclient_daemon.state == NTP_STOPPED) + { + /* Is this the first time that the NTP daemon has been started? */ + + if (g_ntpclient_daemon.state == NTP_NOT_RUNNING) + { + /* Yes... then we will need to initialize the state structure */ + + sem_init(&g_ntpclient_daemon.interlock, 0, 0); + } + + /* Start the NTP daemon */ + + g_ntpclient_daemon.state = NTP_STARTED; + g_ntpclient_daemon.pid = + TASK_CREATE("NTP daemon", CONFIG_NETUTILS_NTPCLIENT_SERVERPRIO, + CONFIG_NETUTILS_NTPCLIENT_STACKSIZE, ntpclient_daemon, + NULL); + + /* Handle failures to start the NTP daemon */ + + if (g_ntpclient_daemon.pid < 0) + { + int errval = errno; + DEBUGASSERT(errval > 0); + + g_ntpclient_daemon.state = NTP_STOPPED; + ndbg("ERROR: Failed to start the NTP daemon\n", errval); + return -errval; + } + + /* Wait for any daemon state change */ + + do + { + (void)sem_wait(&g_ntpclient_daemon.interlock); + } + while (g_ntpclient_daemon.state == NTP_STARTED); + } + + sched_unlock(); + return OK; +} + +/**************************************************************************** + * Name: ntpclient_stop + * + * Description: + * Stop the NTP daemon + * + ****************************************************************************/ + +int ntpclient_stop(void) +{ + /* Is the NTP in a running state? */ + + sched_lock(); + if (g_ntpclient_daemon.state == NTP_STARTED || + g_ntpclient_daemon.state == NTP_RUNNING) + { + /* Yes.. request that the daemon stop. */ + + g_ntpclient_daemon.state = NTP_STOP_REQUESTED; + + /* Wait for any daemon state change */ + + do + { + (void)sem_wait(&g_ntpclient_daemon.interlock); + } + while (g_ntpclient_daemon.state == NTP_STOP_REQUESTED); + } + + sched_unlock(); + return OK; +} diff --git a/apps/netutils/ntpclient/ntpv3.h b/apps/netutils/ntpclient/ntpv3.h new file mode 100755 index 000000000..c96883f82 --- /dev/null +++ b/apps/netutils/ntpclient/ntpv3.h @@ -0,0 +1,207 @@ +/**************************************************************************** + * apps/netutils/ntpclient/ntpv3.h + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +#ifndef __APPS_NETUTILS_NTPCLIENT_NTPV3_H +#define __APPS_NETUTILS_NTPCLIENT_NTPV3_H 1 + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* The NTP version is described in RFC 1305 (NTP version 3), Appendix A: + * + * 0 1 2 3 + * 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * |LI | VN |Mode | Stratum | Poll | Precision | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | Root Delay | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | Root Dispersion | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | Reference Identifier | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | | + * | Reference Timestamp (64) | + * | | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | | + * | Originate Timestamp (64) | + * | | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | | + * | Receive Timestamp (64) | + * | | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | | + * | Transmit Timestamp (64) | + * | | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | Key Identifier (optional) (32) | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + * | | + * | | + * | Message Digest (optional) (128) | + * | | + * | | + * +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + */ + +#define NTP_DATAGRAM_MINSIZE (12 * sizeof(uint32_t)) +#define NTP_DATAGRAM_MAXSIZE (17 * sizeof(uint32_t)) + +/* Leap Indicator (LI): 2-bit code warning of impending leap-second to be + * inserted at the end of the last day of the current month. Bits are coded + * as follows: + * + * 00 no warning + * 01 last minute has 61 seconds + * 10 last minute has 59 seconds + * 11 alarm condition (clock not synchronized) + * + * Version Number (VN): This is a three-bit integer indicating the NTP + * version number. In this case, three (3). + * + * Mode: This is a three-bit integer indicating the mode, with values + * defined as follows: + * + * 0 reserved + * 1 symmetric active + * 2 symmetric passive + * 3 client + * 4 server + * 5 broadcast + * 6 reserved for NTP control message (see Appendix B) + * 7 reserved for private use + * + * Stratum: This is a eight-bit integer indicating the stratum level of the + * local clock, with values defined as follows: + * + * 0 unspecified + * 1 primary reference (e.g., radio clock) + * 2-255 secondary reference (via NTP) + * + * Poll Interval: This is an eight-bit signed integer indicating the maximum + * interval between successive messages, in seconds to the nearest power of + * two. + * + * Precision: This is an eight-bit signed integer indicating the precision + * of the local clock, in seconds to the nearest power of two. + * + * Root Delay: This is a 32-bit signed fixed-point number indicating the + * total roundtrip delay to the primary reference source, in seconds with + * fraction point between bits 15 and 16. Note that this variable can take + * on both positive and negative values, depending on clock precision and + * skew. + * + * Root Dispersion: This is a 32-bit signed fixed-point number indicating + * the maximum error relative to the primary reference source, in seconds + * with fraction point between bits 15 and 16. Only positive values greater + * than zero are possible. + * + * Reference Clock Identifier: This is a 32-bit code identifying the + * particular reference clock. In the case of stratum 0 (unspecified) or + * stratum 1 (primary reference), this is a four-octet, left-justified, + * zero-padded ASCII string. + * + * While not enumerated as part of the NTP specification, the following are + * suggested ASCII identifiers: + * + * Stratum Code Meaning + * 0 DCN DCN routing protocol + * 0 NIST NIST public modem + * 0 TSP TSP time protocol + * 0 DTS Digital Time Service + * 1 ATOM Atomic clock (calibrated) + * 1 VLF VLF radio (OMEGA, etc.) + * 1 callsign Generic radio + * 1 LORC LORAN-C radionavigation + * 1 GOES GOES UHF environment satellite + * 1 GPS GPS UHF satellite positioning + * + * In the case of stratum 2 and greater (secondary reference) this is the + * four-octet Internet address of the primary reference host. + * + * Reference Timestamp: This is the local time at which the local clock was + * last set or corrected, in 64-bit timestamp format. + * + * Originate Timestamp: This is the local time at which the request departed + * the client host for the service host, in 64-bit timestamp format. + * + * Receive Timestamp: This is the local time at which the request arrived at + * the service host, in 64-bit timestamp format. + * + * Transmit Timestamp: This is the local time at which the reply departed + * the service host for the client host, in 64-bit timestamp format. + * + * Authenticator (optional): When the NTP authentication mechanism is + * implemented, this contains the authenticator information defined in + * Appendix C. + */ + +#define MKLVM(l,v,m) ((uint8_t)(l) << 6 | (uint8_t)(v) << 3 | (uint8_t)(m)) +#define GETLI(lvm) ((uint8_t)(lvm) >> 6) +#define GETVN(lvm) ((uint8_t)(lvm) >> 3) & 7) +#define GETMODE(lvm) ((uint8_t)(lvm) & 7) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct ntp_datagram_s +{ + uint8_t lvm; /* LI | VN | Mode */ + uint8_t stratum; /* Stratum */ + uint8_t poll; /* Poll interval */ + uint8_t precision; /* Precision */ + uint8_t rootdelay[4]; /* Root Delay */ + uint8_t rootdispersion[4]; /* Root dispersion */ + uint8_t refid[4]; /* Reference Clock Identifier */ + uint8_t reftimestamp[8]; /* Rererence Timestamp */ + uint8_t origtimestamp[8]; /* Originate Timestamp */ + uint8_t recvtimestamp[8]; /* Receive Timestamp */ + uint8_t xmittimestamp[8]; /* Transmit Timestamp */ + uint8_t keyid[4]; /* Authenticator data */ + uint8_t digest1[4]; + uint8_t digest2[4]; + uint8_t digest3[4]; + uint8_t digest4[4]; +}; + +#endif /* __APPS_NETUTILS_NTPCLIENT_NTPV3_H */ -- cgit v1.2.3