aboutsummaryrefslogtreecommitdiff
path: root/apps/examples
diff options
context:
space:
mode:
Diffstat (limited to 'apps/examples')
-rw-r--r--apps/examples/README.txt4
-rw-r--r--apps/examples/adc/adc.h4
-rw-r--r--apps/examples/buttons/buttons_main.c28
-rw-r--r--apps/examples/can/can.h4
-rw-r--r--apps/examples/cdcacm/cdcacm.h4
-rw-r--r--apps/examples/control_demo/params.c6
-rw-r--r--apps/examples/kalman_demo/KalmanNav.cpp23
-rw-r--r--apps/examples/ostest/ostest_main.c28
-rw-r--r--apps/examples/ostest/waitpid.c18
-rw-r--r--apps/examples/poll/Kconfig18
-rw-r--r--apps/examples/poll/poll_internal.h6
-rw-r--r--apps/examples/pwm/pwm.h4
-rw-r--r--apps/examples/qencoder/qe.h4
-rw-r--r--apps/examples/watchdog/watchdog.h4
14 files changed, 101 insertions, 54 deletions
diff --git a/apps/examples/README.txt b/apps/examples/README.txt
index 5996cbb70..03d43f1a0 100644
--- a/apps/examples/README.txt
+++ b/apps/examples/README.txt
@@ -675,8 +675,8 @@ examples/mount
when CONFIG_EXAMPLES_MOUNT_DEVNAME is not defined. The
default is zero (meaning that "/dev/ram0" will be used).
-examples/netttest
-^^^^^^^^^^^^^^^^^
+examples/nettest
+^^^^^^^^^^^^^^^^
This is a simple network test for verifying client- and server-
functionality in a TCP/IP connection.
diff --git a/apps/examples/adc/adc.h b/apps/examples/adc/adc.h
index 9f79db92a..2d8af87e1 100644
--- a/apps/examples/adc/adc.h
+++ b/apps/examples/adc/adc.h
@@ -74,7 +74,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) syslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -82,7 +82,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message syslog
# define msgflush()
# else
# define message printf
diff --git a/apps/examples/buttons/buttons_main.c b/apps/examples/buttons/buttons_main.c
index 5f25c1ef1..655080def 100644
--- a/apps/examples/buttons/buttons_main.c
+++ b/apps/examples/buttons/buttons_main.c
@@ -299,11 +299,11 @@ static void show_buttons(uint8_t oldset, uint8_t newset)
state = "released";
}
- /* Use lib_lowprintf() because we make be executing from an
+ /* Use lowsyslog() because we make be executing from an
* interrupt handler.
*/
- lib_lowprintf(" %s %s\n", g_buttoninfo[BUTTON_INDEX(i)].name, state);
+ lowsyslog(" %s %s\n", g_buttoninfo[BUTTON_INDEX(i)].name, state);
}
}
}
@@ -313,8 +313,8 @@ static void button_handler(int id, int irq)
{
uint8_t newset = up_buttons();
- lib_lowprintf("IRQ:%d Button %d:%s SET:%02x:\n",
- irq, id, g_buttoninfo[BUTTON_INDEX(id)].name, newset);
+ lowsyslog("IRQ:%d Button %d:%s SET:%02x:\n",
+ irq, id, g_buttoninfo[BUTTON_INDEX(id)].name, newset);
show_buttons(g_oldset, newset);
g_oldset = newset;
}
@@ -409,7 +409,7 @@ int buttons_main(int argc, char *argv[])
{
maxbuttons = strtol(argv[1], NULL, 10);
}
- lib_lowprintf("maxbuttons: %d\n", maxbuttons);
+ lowsyslog("maxbuttons: %d\n", maxbuttons);
#endif
/* Initialize the button GPIOs */
@@ -423,11 +423,11 @@ int buttons_main(int argc, char *argv[])
{
xcpt_t oldhandler = up_irqbutton(i, g_buttoninfo[BUTTON_INDEX(i)].handler);
- /* Use lib_lowprintf() for compatibility with interrrupt handler output. */
+ /* Use lowsyslog() for compatibility with interrrupt handler output. */
- lib_lowprintf("Attached handler at %p to button %d [%s], oldhandler:%p\n",
- g_buttoninfo[BUTTON_INDEX(i)].handler, i,
- g_buttoninfo[BUTTON_INDEX(i)].name, oldhandler);
+ lowsyslog("Attached handler at %p to button %d [%s], oldhandler:%p\n",
+ g_buttoninfo[BUTTON_INDEX(i)].handler, i,
+ g_buttoninfo[BUTTON_INDEX(i)].name, oldhandler);
/* Some hardware multiplexes different GPIO button sources to the same
* physical interrupt. If we register multiple such multiplexed button
@@ -438,9 +438,9 @@ int buttons_main(int argc, char *argv[])
if (oldhandler != NULL)
{
- lib_lowprintf("WARNING: oldhandler:%p is not NULL! "
- "Button events may be lost or aliased!\n",
- oldhandler);
+ lowsyslog("WARNING: oldhandler:%p is not NULL! "
+ "Button events may be lost or aliased!\n",
+ oldhandler);
}
}
#endif
@@ -468,11 +468,11 @@ int buttons_main(int argc, char *argv[])
flags = irqsave();
- /* Use lib_lowprintf() for compatibility with interrrupt handler
+ /* Use lowsyslog() for compatibility with interrrupt handler
* output.
*/
- lib_lowprintf("POLL SET:%02x:\n", newset);
+ lowsyslog("POLL SET:%02x:\n", newset);
show_buttons(g_oldset, newset);
g_oldset = newset;
irqrestore(flags);
diff --git a/apps/examples/can/can.h b/apps/examples/can/can.h
index 53a6b63ea..d9f9236f7 100644
--- a/apps/examples/can/can.h
+++ b/apps/examples/can/can.h
@@ -89,7 +89,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) syslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -97,7 +97,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message syslog
# define msgflush()
# else
# define message printf
diff --git a/apps/examples/cdcacm/cdcacm.h b/apps/examples/cdcacm/cdcacm.h
index 18570bff0..1b3b2511c 100644
--- a/apps/examples/cdcacm/cdcacm.h
+++ b/apps/examples/cdcacm/cdcacm.h
@@ -112,7 +112,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_lowprintf(__VA_ARGS__)
+# define message(...) lowsyslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -120,7 +120,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_lowprintf
+# define message lowsyslog
# define msgflush()
# else
# define message printf
diff --git a/apps/examples/control_demo/params.c b/apps/examples/control_demo/params.c
index 6525b70f5..8cefc298f 100644
--- a/apps/examples/control_demo/params.c
+++ b/apps/examples/control_demo/params.c
@@ -52,9 +52,9 @@ PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90
PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain
// speed command
-PARAM_DEFINE_FLOAT(FWB_V_MIN, 20.0f); // minimum commanded velocity
-PARAM_DEFINE_FLOAT(FWB_V_CMD, 22.0f); // commanded velocity
-PARAM_DEFINE_FLOAT(FWB_V_MAX, 24.0f); // maximum commanded velocity
+PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity
+PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity
+PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity
// trim
PARAM_DEFINE_FLOAT(FWB_TRIM_AIL, 0.0f); // trim aileron, normalized (-1,1)
diff --git a/apps/examples/kalman_demo/KalmanNav.cpp b/apps/examples/kalman_demo/KalmanNav.cpp
index 1d59f9677..db851221b 100644
--- a/apps/examples/kalman_demo/KalmanNav.cpp
+++ b/apps/examples/kalman_demo/KalmanNav.cpp
@@ -190,11 +190,12 @@ void KalmanNav::update()
if (!_positionInitialized &&
_attitudeInitialized && // wait for attitude first
gpsUpdate &&
- _gps.fix_type > 2 &&
- _gps.counter_pos_valid > 10) {
- vN = _gps.vel_n;
- vE = _gps.vel_e;
- vD = _gps.vel_d;
+ _gps.fix_type > 2
+ //&& _gps.counter_pos_valid > 10
+ ) {
+ vN = _gps.vel_n_m_s;
+ vE = _gps.vel_e_m_s;
+ vD = _gps.vel_d_m_s;
setLatDegE7(_gps.lat);
setLonDegE7(_gps.lon);
setAltE3(_gps.alt);
@@ -259,7 +260,7 @@ void KalmanNav::updatePublications()
// position publication
_pos.timestamp = _pubTimeStamp;
- _pos.time_gps_usec = _gps.timestamp;
+ _pos.time_gps_usec = _gps.timestamp_position;
_pos.valid = true;
_pos.lat = getLatDegE7();
_pos.lon = getLonDegE7();
@@ -630,8 +631,8 @@ int KalmanNav::correctPos()
// residual
Vector y(5);
- y(0) = _gps.vel_n - vN;
- y(1) = _gps.vel_e - vE;
+ y(0) = _gps.vel_n_m_s - vN;
+ y(1) = _gps.vel_e_m_s - vE;
y(2) = double(_gps.lat) - lat * 1.0e7 * M_RAD_TO_DEG;
y(3) = double(_gps.lon) - lon * 1.0e7 * M_RAD_TO_DEG;
y(4) = double(_gps.alt) / 1.0e3 - alt;
@@ -650,9 +651,9 @@ int KalmanNav::correctPos()
// abort correction and return
printf("[kalman_demo] numerical failure in gps correction\n");
// fallback to GPS
- vN = _gps.vel_n;
- vE = _gps.vel_e;
- vD = _gps.vel_d;
+ vN = _gps.vel_n_m_s;
+ vE = _gps.vel_e_m_s;
+ vD = _gps.vel_d_m_s;
setLatDegE7(_gps.lat);
setLonDegE7(_gps.lon);
setAltE3(_gps.alt);
diff --git a/apps/examples/ostest/ostest_main.c b/apps/examples/ostest/ostest_main.c
index aab1ff045..3e4197fdc 100644
--- a/apps/examples/ostest/ostest_main.c
+++ b/apps/examples/ostest/ostest_main.c
@@ -43,8 +43,11 @@
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
+#include <signal.h>
#include <string.h>
#include <sched.h>
+#include <errno.h>
+
#include <nuttx/init.h>
#include "ostest.h"
@@ -264,6 +267,31 @@ static int user_main(int argc, char *argv[])
}
check_test_memory_usage();
+ /* If retention of child status is enable, then suppress it for this task.
+ * This task may produce many, many children (especially if
+ * CONFIG_EXAMPLES_OSTEST_LOOPS) and it does not harvest their exit status.
+ * As a result, the test may fail inappropriately unless retention of
+ * child exit status is disabled.
+ *
+ * So basically, this tests that child status can be disabled, but cannot
+ * verify that status is retained correctly.
+ */
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+ {
+ struct sigaction sa;
+ int ret;
+
+ sa.sa_handler = SIG_IGN;
+ sa.sa_flags = SA_NOCLDWAIT;
+ ret = sigaction(SIGCHLD, &sa, NULL);
+ if (ret < 0)
+ {
+ printf("user_main: ERROR: sigaction failed: %d\n", errno);
+ }
+ }
+#endif
+
/* Check environment variables */
#ifndef CONFIG_DISABLE_ENVIRON
show_environment(true, true, true);
diff --git a/apps/examples/ostest/waitpid.c b/apps/examples/ostest/waitpid.c
index e53b49213..d45410265 100644
--- a/apps/examples/ostest/waitpid.c
+++ b/apps/examples/ostest/waitpid.c
@@ -113,14 +113,14 @@ static void waitpid_last(void)
printf("waitpid_last: ERROR: PID %d waitpid failed: %d\n",
g_waitpids[NCHILDREN-1], errcode);
}
- else if (stat_loc != RETURN_STATUS)
+ else if (WEXITSTATUS(stat_loc) != RETURN_STATUS)
{
printf("waitpid_last: ERROR: PID %d return status is %d, expected %d\n",
- g_waitpids[NCHILDREN-1], stat_loc, RETURN_STATUS);
+ g_waitpids[NCHILDREN-1], WEXITSTATUS(stat_loc), RETURN_STATUS);
}
else
{
- printf("waitpid_last: PID %d waitpid succeeded with stat_loc=%d\n",
+ printf("waitpid_last: PID %d waitpid succeeded with stat_loc=%04x\n",
g_waitpids[NCHILDREN-1], stat_loc);
}
}
@@ -155,14 +155,14 @@ int waitpid_test(void)
printf("waitpid_test: ERROR: PID %d wait returned PID %d\n",
g_waitpids[0], ret);
}
- else if (stat_loc != RETURN_STATUS)
+ else if (WEXITSTATUS(stat_loc) != RETURN_STATUS)
{
printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n",
- g_waitpids[0], stat_loc, RETURN_STATUS);
+ g_waitpids[0], WEXITSTATUS(stat_loc), RETURN_STATUS);
}
else
{
- printf("waitpid_test: PID %d waitpid succeeded with stat_loc=%d\n",
+ printf("waitpid_test: PID %d waitpid succeeded with stat_loc=%04x\n",
g_waitpids[0], stat_loc);
}
@@ -246,14 +246,14 @@ int waitpid_test(void)
int errcode = errno;
printf("waitpid_test: ERROR: wait failed: %d\n", errcode);
}
- else if (stat_loc != RETURN_STATUS)
+ else if (WEXITSTATUS(stat_loc) != RETURN_STATUS)
{
printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n",
- ret, stat_loc, RETURN_STATUS);
+ ret, WEXITSTATUS(stat_loc), RETURN_STATUS);
}
else
{
- printf("waitpid_test: PID %d wait succeeded with stat_loc=%d\n",
+ printf("waitpid_test: PID %d wait succeeded with stat_loc=%04x\n",
ret, stat_loc);
}
diff --git a/apps/examples/poll/Kconfig b/apps/examples/poll/Kconfig
index c52827496..f35a9200b 100644
--- a/apps/examples/poll/Kconfig
+++ b/apps/examples/poll/Kconfig
@@ -6,8 +6,26 @@
config EXAMPLES_POLL
bool "Poll example"
default n
+ depends on !NSH_BUILTIN_APPS
---help---
Enable the poll example
if EXAMPLES_POLL
+
+config EXAMPLES_POLL_NOMAC
+ bool "Use Canned MAC Address"
+ default n
+
+config EXAMPLES_POLL_IPADDR
+ hex "Target IP address"
+ default 0x0a000002
+
+config EXAMPLES_POLL_DRIPADDR
+ hex "Default Router IP address (Gateway)"
+ default 0x0a000001
+
+config EXAMPLES_POLL_NETMASK
+ hex "Network Mask"
+ default 0xffffff00
+
endif
diff --git a/apps/examples/poll/poll_internal.h b/apps/examples/poll/poll_internal.h
index b2400932e..759d23f1c 100644
--- a/apps/examples/poll/poll_internal.h
+++ b/apps/examples/poll/poll_internal.h
@@ -71,7 +71,7 @@
# undef HAVE_NETPOLL
#endif
-/* If debug is enabled, then use lib_rawprintf so that OS debug output and
+/* If debug is enabled, then use syslog so that OS debug output and
* the test output are synchronized.
*
* These macros will differ depending upon if the toolchain supports
@@ -80,7 +80,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) syslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -88,7 +88,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message syslog
# define msgflush()
# else
# define message printf
diff --git a/apps/examples/pwm/pwm.h b/apps/examples/pwm/pwm.h
index 5c049a8f8..a6132ca8b 100644
--- a/apps/examples/pwm/pwm.h
+++ b/apps/examples/pwm/pwm.h
@@ -92,7 +92,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) syslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -100,7 +100,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message syslog
# define msgflush()
# else
# define message printf
diff --git a/apps/examples/qencoder/qe.h b/apps/examples/qencoder/qe.h
index 4c03689ab..3c20511ca 100644
--- a/apps/examples/qencoder/qe.h
+++ b/apps/examples/qencoder/qe.h
@@ -77,7 +77,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) syslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -85,7 +85,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message syslog
# define msgflush()
# else
# define message printf
diff --git a/apps/examples/watchdog/watchdog.h b/apps/examples/watchdog/watchdog.h
index dc2dea944..dd4daebb9 100644
--- a/apps/examples/watchdog/watchdog.h
+++ b/apps/examples/watchdog/watchdog.h
@@ -89,7 +89,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) syslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -97,7 +97,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message syslog
# define msgflush()
# else
# define message printf