summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-04-15 11:00:40 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-04-15 11:00:40 -0600
commitf81bf58d9a79205e0aa94713c1db9bddefa984d1 (patch)
treef39712ae454aa59ed8a01900c5ef356e7039776b /nuttx
parentd12f3d6b20380a2a886d270a432f8e26e7b9c2a5 (diff)
downloadpx4-nuttx-f81bf58d9a79205e0aa94713c1db9bddefa984d1.tar.gz
px4-nuttx-f81bf58d9a79205e0aa94713c1db9bddefa984d1.tar.bz2
px4-nuttx-f81bf58d9a79205e0aa94713c1db9bddefa984d1.zip
configs/sim/src: Add logic to test localtime and TZ database. See apps/system/README.txt for info
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/configs/sim/src/Makefile4
-rw-r--r--nuttx/configs/sim/src/sim.h96
-rw-r--r--nuttx/configs/sim/src/sim_boot.c8
-rw-r--r--nuttx/configs/sim/src/sim_zoneinfo.c153
-rw-r--r--nuttx/libc/Kconfig19
5 files changed, 277 insertions, 3 deletions
diff --git a/nuttx/configs/sim/src/Makefile b/nuttx/configs/sim/src/Makefile
index c07947f97..5afc39fb3 100644
--- a/nuttx/configs/sim/src/Makefile
+++ b/nuttx/configs/sim/src/Makefile
@@ -45,6 +45,9 @@ CSRCS =
ifeq ($(CONFIG_BOARD_INITIALIZE),y)
CSRCS += sim_boot.c
+ifeq ($(CONFIG_SYSTEM_ZONEINFO_ROMFS),y)
+ CSRCS += sim_zoneinfo.c
+endif
endif
ifeq ($(CONFIG_SIM_X11FB),y)
@@ -52,6 +55,7 @@ ifeq ($(CONFIG_SIM_TOUCHSCREEN),y)
CSRCS += sim_touchscreen.c
endif
endif
+
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/sim/src/sim.h b/nuttx/configs/sim/src/sim.h
new file mode 100644
index 000000000..ce96c2ba0
--- /dev/null
+++ b/nuttx/configs/sim/src/sim.h
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * config/sim/src/sim.h
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 __CONFIGS_SIM_SRC_SIM_H
+#define __CONFIGS_SIM_SRC_SIM_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sim_zoneinfo
+ *
+ * Description:
+ * Mount the TZ database. The apps/system/zoneinfo directory contains
+ * logic to create a version of the TZ/Olson database.
+ * This database is required if localtime() support is selected via
+ * CONFIG_LIBC_LOCALTIME. This logic in that directory does the following:
+ *
+ * - It downloads the current TZ database from the IANA website
+ * - It downloads the current timezone tools from the same location
+ * - It builds the tools and constructs the binary TZ database
+ * - It will then, optionally, build a ROMFS filesystem image containing
+ * the data base.
+ *
+ * The ROMFS filesystem image can that be mounted during the boot-up sequence
+ * so that it is available for the localtime logic. There are two steps to
+ * doing this:
+ *
+ * - First, a ROM disk device must be created. This is done by calling
+ * the function romdisk_register() as described in
+ * nuttx/include/nuttx/fs/ramdisk.h. This is an OS level operation
+ * and must be done in the board-level logic before your appliction
+ * starts.
+ *
+ * romdisk_register() will create a block driver at /dev/ramN where N
+ * is the device minor number that was provdied to romdisk_regsiter.
+ *
+ * - The second step is to mount the file system. This step can be
+ * performed either in your board configuration logic or by your
+ * application using the mount() interface described in
+ * nuttx/include/sys/mount.h.
+ *
+ * These steps, however, must be done very early in initialization,
+ * before there is any need for time-related services.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SYSTEM_ZONEINFO_ROMFS
+int sim_zoneinfo(int minor);
+#endif
+
+
+#endif /* __CONFIGS_SIM_SRC_SIM_H */ \ No newline at end of file
diff --git a/nuttx/configs/sim/src/sim_boot.c b/nuttx/configs/sim/src/sim_boot.c
index 4b581ef52..68ee751c6 100644
--- a/nuttx/configs/sim/src/sim_boot.c
+++ b/nuttx/configs/sim/src/sim_boot.c
@@ -42,6 +42,7 @@
#include <nuttx/board.h>
#include "up_internal.h"
+#include "sim.h"
#ifdef CONFIG_GRAPHICS_TRAVELER_ROMFSDEMO
int trv_mount_world(int minor, FAR const char *mountpoint);
@@ -83,6 +84,12 @@ int trv_mount_world(int minor, FAR const char *mountpoint);
#ifdef CONFIG_BOARD_INITIALIZE
void board_initialize(void)
{
+#ifdef CONFIG_SYSTEM_ZONEINFO_ROMFS
+ /* Mount the TZ database */
+
+ (void)sim_zoneinfo(3);
+#endif
+
#ifdef CONFIG_AJOYSTICK
/* Initialize the simulated analog joystick input device */
@@ -93,7 +100,6 @@ void board_initialize(void)
/* Special initialization for the Traveler game simulation */
(void)trv_mount_world(0, CONFIG_GRAPHICS_TRAVELER_DEFPATH);
-
#endif
}
diff --git a/nuttx/configs/sim/src/sim_zoneinfo.c b/nuttx/configs/sim/src/sim_zoneinfo.c
new file mode 100644
index 000000000..1e3840917
--- /dev/null
+++ b/nuttx/configs/sim/src/sim_zoneinfo.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * config/sim/src/sim_zoneinfo.c
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <nuttx/config.h>
+
+#include <sys/mount.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <errno.h>
+
+#include <nuttx/fs/ramdisk.h>
+#include <apps/zoneinfo.h>
+
+#ifdef CONFIG_SYSTEM_ZONEINFO_ROMFS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifndef CONFIG_LIBC_TZDIR
+# errror CONFIG_LIBC_TZDIR is not defined
+#endif
+
+#ifdef CONFIG_DISABLE_MOUNTPOINT
+# error "Mountpoint support is disabled"
+#endif
+
+#if CONFIG_NFILE_DESCRIPTORS < 4
+# error "Not enough file descriptors"
+#endif
+
+#ifndef CONFIG_FS_ROMFS
+# error "ROMFS support not enabled"
+#endif
+
+#define SECTORSIZE 64
+#define NSECTORS(b) (((b)+SECTORSIZE-1)/SECTORSIZE)
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sim_zoneinfo
+ *
+ * Description:
+ * Mount the TZ database. The apps/system/zoneinfo directory contains
+ * logic to create a version of the TZ/Olson database.
+ * This database is required if localtime() support is selected via
+ * CONFIG_LIBC_LOCALTIME. This logic in that directory does the following:
+ *
+ * - It downloads the current TZ database from the IANA website
+ * - It downloads the current timezone tools from the same location
+ * - It builds the tools and constructs the binary TZ database
+ * - It will then, optionally, build a ROMFS filesystem image containing
+ * the data base.
+ *
+ * The ROMFS filesystem image can that be mounted during the boot-up sequence
+ * so that it is available for the localtime logic. There are two steps to
+ * doing this:
+ *
+ * - First, a ROM disk device must be created. This is done by calling
+ * the function romdisk_register() as described in
+ * nuttx/include/nuttx/fs/ramdisk.h. This is an OS level operation
+ * and must be done in the board-level logic before your appliction
+ * starts.
+ *
+ * romdisk_register() will create a block driver at /dev/ramN where N
+ * is the device minor number that was provdied to romdisk_regsiter.
+ *
+ * - The second step is to mount the file system. This step can be
+ * performed either in your board configuration logic or by your
+ * application using the mount() interface described in
+ * nuttx/include/sys/mount.h.
+ *
+ * These steps, however, must be done very early in initialization,
+ * before there is any need for time-related services.
+ *
+ ****************************************************************************/
+
+int sim_zoneinfo(int minor)
+{
+ char devname[32];
+ int ret;
+
+ /* Create a RAM disk for the test */
+
+ ret = romdisk_register(minor, romfs_zoneinfo_img,
+ NSECTORS(romfs_zoneinfo_img_len), SECTORSIZE);
+ if (ret < 0)
+ {
+ printf("ERROR: Failed to create RAM disk\n");
+ return ret;
+ }
+
+ /* Use the minor number to create a name for the ROM disk block device */
+
+ snprintf(devname, 32, "/dev/ram%d", minor);
+
+ /* Mount the ROMFS file system */
+
+ printf("Mounting ROMFS filesystem at target=%s with source=%s\n",
+ CONFIG_LIBC_TZDIR, devname);
+
+ ret = mount(devname, CONFIG_LIBC_TZDIR, "romfs", MS_RDONLY, NULL);
+ if (ret < 0)
+ {
+ printf("ERROR: Mount failed: %d\n", errno);
+ return ret;
+ }
+
+ printf("TZ database mounted at %s\n", CONFIG_LIBC_TZDIR);
+ return OK;
+}
+
+#endif /* CONFIG_SYSTEM_ZONEINFO_ROMFS */
+
diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig
index 7e8e81f5e..9aedf7b85 100644
--- a/nuttx/libc/Kconfig
+++ b/nuttx/libc/Kconfig
@@ -281,15 +281,30 @@ if LIBC_LOCALTIME
config LIBC_TZ_MAX_TIMES
int "Maximum number of times in timezone"
- default 8
+ default 370
+ ---help---
+ Timezone files with more than this number of times will not be usedi
+ (tmecnt).
+
+ Warning: Some files in IANA TZ database include many more times than
+ this. The current posixrules file, for example, has timecnt = 236.
+ The value of TX_MAX_ITMES in the tzfile.h header file on my Linux
+ system is 370. You may want to reduce this value for a smaller
+ footprint.
config LIBC_TZ_MAX_TYPES
int "Maximum number of TZ types"
- default 8
+ default 20
+ ---help---
+ Maximum number of local time types. You may want to reduce this value
+ for a smaller footprint.
config LIBC_TZDIR
string "zoneinfo directory path"
default "/etc/zoneinfo"
+ ---help---
+ This is the full path to the location where the TZ database is expected
+ to be found.
endif