aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-02-18 16:46:05 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-02-18 16:46:05 +0100
commit663ca58063a281d23dbc92a6fbd19011c3fbde41 (patch)
tree5a2e9f58a8f41db94ef221e12acead09c9828233
parent104d5aa3654545b354f25750d3980181da8f6a0b (diff)
parent520a2b417410bed7db6f08a3a69f3bcccc55910b (diff)
downloadpx4-firmware-663ca58063a281d23dbc92a6fbd19011c3fbde41.tar.gz
px4-firmware-663ca58063a281d23dbc92a6fbd19011c3fbde41.tar.bz2
px4-firmware-663ca58063a281d23dbc92a6fbd19011c3fbde41.zip
Merge branch 'master' of github.com:PX4/Firmware
-rwxr-xr-xROMFS/logging/logconv.m7
-rw-r--r--ROMFS/scripts/rc.FMU_quad_x83
-rw-r--r--ROMFS/scripts/rc.PX4IO87
-rw-r--r--ROMFS/scripts/rc.PX4IOAR36
-rw-r--r--apps/ChangeLog.txt21
-rw-r--r--apps/builtin/exec_builtin.c2
-rw-r--r--apps/commander/commander.c26
-rw-r--r--apps/drivers/boards/px4fmu/px4fmu_init.c4
-rw-r--r--apps/drivers/drv_gps.h70
-rw-r--r--apps/drivers/gps/Makefile (renamed from apps/gps/Makefile)19
-rw-r--r--apps/drivers/gps/gps.cpp536
-rw-r--r--apps/drivers/gps/gps_helper.cpp92
-rw-r--r--apps/drivers/gps/gps_helper.h52
-rw-r--r--apps/drivers/gps/mtk.cpp274
-rw-r--r--apps/drivers/gps/mtk.h124
-rw-r--r--apps/drivers/gps/ubx.cpp745
-rw-r--r--apps/drivers/gps/ubx.h395
-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
-rw-r--r--apps/gps/.context0
-rw-r--r--apps/gps/.gitignore3
-rw-r--r--apps/gps/gps.c589
-rw-r--r--apps/gps/gps.h18
-rw-r--r--apps/gps/mtk.c432
-rw-r--r--apps/gps/mtk.h98
-rw-r--r--apps/gps/nmea_helper.c345
-rw-r--r--apps/gps/nmea_helper.h47
-rw-r--r--apps/gps/nmealib/LICENSE.TXT506
-rw-r--r--apps/gps/nmealib/README.TXT26
-rw-r--r--apps/gps/nmealib/context.c67
-rw-r--r--apps/gps/nmealib/generate.c229
-rw-r--r--apps/gps/nmealib/generator.c399
-rw-r--r--apps/gps/nmealib/gmath.c376
-rw-r--r--apps/gps/nmealib/info.c21
-rw-r--r--apps/gps/nmealib/nmea/config.h51
-rw-r--r--apps/gps/nmealib/nmea/context.h44
-rw-r--r--apps/gps/nmealib/nmea/generate.h44
-rw-r--r--apps/gps/nmealib/nmea/generator.h79
-rw-r--r--apps/gps/nmealib/nmea/gmath.h92
-rw-r--r--apps/gps/nmealib/nmea/info.h112
-rw-r--r--apps/gps/nmealib/nmea/nmea.h25
-rw-r--r--apps/gps/nmealib/nmea/parse.h39
-rw-r--r--apps/gps/nmealib/nmea/parser.h59
-rw-r--r--apps/gps/nmealib/nmea/sentence.h128
-rw-r--r--apps/gps/nmealib/nmea/time.h47
-rw-r--r--apps/gps/nmealib/nmea/tok.h31
-rw-r--r--apps/gps/nmealib/nmea/units.h30
-rw-r--r--apps/gps/nmealib/parse.c501
-rw-r--r--apps/gps/nmealib/parser.c400
-rw-r--r--apps/gps/nmealib/sentence.c54
-rw-r--r--apps/gps/nmealib/time.c63
-rw-r--r--apps/gps/nmealib/tok.c267
-rw-r--r--apps/gps/ubx.c1022
-rw-r--r--apps/gps/ubx.h415
-rw-r--r--apps/include/nsh.h71
-rw-r--r--apps/include/usbmonitor.h (renamed from nuttx/sched/env_dupenv.c)96
-rw-r--r--apps/mavlink/mavlink.c10
-rw-r--r--apps/mavlink/mavlink_receiver.c24
-rw-r--r--apps/mavlink/orb_listener.c12
-rw-r--r--apps/nshlib/Kconfig42
-rw-r--r--apps/nshlib/Makefile9
-rw-r--r--apps/nshlib/README.txt12
-rw-r--r--apps/nshlib/nsh.h123
-rw-r--r--apps/nshlib/nsh_consolemain.c88
-rw-r--r--apps/nshlib/nsh_ddcmd.c2
-rw-r--r--apps/nshlib/nsh_fscmds.c67
-rw-r--r--apps/nshlib/nsh_script.c195
-rw-r--r--apps/nshlib/nsh_session.c163
-rw-r--r--apps/nshlib/nsh_telnetd.c33
-rw-r--r--apps/nshlib/nsh_usbdev.c258
-rw-r--r--apps/px4/tests/test_adc.c8
-rw-r--r--apps/px4/tests/tests.h4
-rw-r--r--apps/px4/tests/tests_main.c12
-rw-r--r--apps/px4io/mixer.cpp4
-rw-r--r--apps/px4io/px4io.c4
-rw-r--r--apps/px4io/px4io.h2
-rw-r--r--apps/system/Kconfig4
-rw-r--r--apps/system/Make.defs3
-rw-r--r--apps/system/Makefile2
-rw-r--r--apps/system/free/README.txt6
-rw-r--r--apps/system/readline/readline.c52
-rw-r--r--apps/system/usbmonitor/Kconfig67
-rw-r--r--apps/system/usbmonitor/Makefile117
-rw-r--r--apps/system/usbmonitor/usbmonitor.c234
-rw-r--r--apps/systemlib/err.c8
-rw-r--r--apps/systemlib/mixer/mixer_group.cpp2
-rw-r--r--apps/systemlib/mixer/mixer_multirotor.cpp6
-rw-r--r--apps/uORB/topics/home_position.h8
-rw-r--r--apps/uORB/topics/vehicle_gps_position.h55
-rw-r--r--nuttx/ChangeLog101
-rw-r--r--nuttx/Kconfig55
-rw-r--r--nuttx/README.txt55
-rw-r--r--nuttx/ReleaseNotes320
-rw-r--r--nuttx/TODO86
-rw-r--r--nuttx/arch/arm/src/armv7-m/Toolchain.defs42
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_assert.c7
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/arm/src/common/up_exit.c46
-rw-r--r--nuttx/arch/arm/src/common/up_initialize.c14
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h17
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_spi.h8
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.c315
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.h6
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c91
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c129
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_spi.c51
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbdev.c14
-rw-r--r--nuttx/binfmt/Kconfig5
-rw-r--r--nuttx/binfmt/binfmt_execmodule.c61
-rw-r--r--nuttx/binfmt/binfmt_internal.h2
-rw-r--r--nuttx/binfmt/libelf/libelf_read.c2
-rw-r--r--nuttx/binfmt/libnxflat/libnxflat_read.c2
-rw-r--r--nuttx/configs/README.txt2
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig2
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig1
-rwxr-xr-xnuttx/configs/px4io/io/defconfig1
-rw-r--r--nuttx/drivers/Kconfig8
-rw-r--r--nuttx/drivers/lcd/mio283qt2.c6
-rw-r--r--nuttx/drivers/lcd/ssd1289.c6
-rw-r--r--nuttx/drivers/loop.c2
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_debug.c4
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c10
-rw-r--r--nuttx/drivers/mtd/at25.c16
-rw-r--r--nuttx/drivers/net/enc28j60.c96
-rw-r--r--nuttx/drivers/serial/Kconfig3
-rw-r--r--nuttx/drivers/serial/serial.c221
-rw-r--r--nuttx/drivers/syslog/ramlog.c6
-rw-r--r--nuttx/drivers/usbdev/Kconfig44
-rw-r--r--nuttx/drivers/usbdev/cdcacm.c137
-rw-r--r--nuttx/drivers/usbdev/pl2303.c129
-rw-r--r--nuttx/drivers/usbdev/usbdev_trace.c4
-rw-r--r--nuttx/drivers/usbdev/usbmsc.h8
-rw-r--r--nuttx/fs/Kconfig42
-rw-r--r--nuttx/fs/fat/fs_configfat.c14
-rw-r--r--nuttx/fs/fat/fs_fat32.c3
-rw-r--r--nuttx/fs/fat/fs_fat32util.c4
-rw-r--r--nuttx/fs/fs_fdopen.c13
-rw-r--r--nuttx/fs/fs_files.c101
-rw-r--r--nuttx/fs/fs_syslog.c59
-rw-r--r--nuttx/fs/nxffs/nxffs_dump.c2
-rw-r--r--nuttx/graphics/nxfonts/nxfonts_getfont.c2
-rw-r--r--nuttx/include/assert.h21
-rw-r--r--nuttx/include/debug.h37
-rw-r--r--nuttx/include/nuttx/fs/fs.h90
-rw-r--r--nuttx/include/nuttx/lib.h9
-rw-r--r--nuttx/include/nuttx/net/net.h87
-rw-r--r--nuttx/include/nuttx/sched.h199
-rw-r--r--nuttx/include/nuttx/serial/serial.h76
-rw-r--r--nuttx/include/nuttx/syslog.h6
-rw-r--r--nuttx/include/nuttx/usb/cdcacm.h12
-rw-r--r--nuttx/include/nuttx/usb/usbdev_trace.h5
-rw-r--r--nuttx/include/syslog.h (renamed from nuttx/sched/env_share.c)93
-rw-r--r--nuttx/libc/lib.csv6
-rw-r--r--nuttx/libc/misc/lib_dbg.c36
-rw-r--r--nuttx/libc/misc/lib_dumpbuffer.c8
-rw-r--r--nuttx/libc/misc/lib_init.c134
-rw-r--r--nuttx/libc/stdio/Make.defs2
-rw-r--r--nuttx/libc/stdio/lib_fgets.c2
-rw-r--r--nuttx/libc/stdio/lib_libflushall.c2
-rw-r--r--nuttx/libc/stdio/lib_libfread.c4
-rw-r--r--nuttx/libc/stdio/lib_lowsyslog.c (renamed from nuttx/libc/stdio/lib_lowprintf.c)18
-rw-r--r--nuttx/libc/stdio/lib_printf.c4
-rw-r--r--nuttx/libc/stdio/lib_syslog.c (renamed from nuttx/libc/stdio/lib_rawprintf.c)23
-rw-r--r--nuttx/libc/stdio/lib_syslogstream.c15
-rw-r--r--nuttx/net/net_poll.c160
-rw-r--r--nuttx/net/net_sockets.c100
-rw-r--r--nuttx/net/send.c2
-rw-r--r--nuttx/sched/Kconfig27
-rw-r--r--nuttx/sched/Makefile34
-rw-r--r--nuttx/sched/env_clearenv.c8
-rw-r--r--nuttx/sched/env_dup.c68
-rw-r--r--nuttx/sched/env_findvar.c33
-rw-r--r--nuttx/sched/env_getenv.c14
-rw-r--r--nuttx/sched/env_internal.h36
-rw-r--r--nuttx/sched/env_release.c67
-rw-r--r--nuttx/sched/env_removevar.c56
-rw-r--r--nuttx/sched/env_setenv.c59
-rw-r--r--nuttx/sched/env_unsetenv.c62
-rw-r--r--nuttx/sched/group_childstatus.c (renamed from nuttx/sched/task_childstatus.c)129
-rw-r--r--nuttx/sched/group_create.c276
-rw-r--r--nuttx/sched/group_find.c125
-rw-r--r--nuttx/sched/group_internal.h (renamed from nuttx/sched/sched_setuppthreadfiles.c)124
-rw-r--r--nuttx/sched/group_join.c227
-rw-r--r--nuttx/sched/group_leave.c366
-rw-r--r--nuttx/sched/group_setupidlefiles.c (renamed from nuttx/sched/sched_setupidlefiles.c)34
-rw-r--r--nuttx/sched/group_setupstreams.c (renamed from nuttx/sched/sched_setupstreams.c)45
-rw-r--r--nuttx/sched/group_setuptaskfiles.c (renamed from nuttx/sched/sched_setuptaskfiles.c)105
-rw-r--r--nuttx/sched/group_signal.c163
-rw-r--r--nuttx/sched/mq_sndinternal.c2
-rw-r--r--nuttx/sched/os_internal.h35
-rw-r--r--nuttx/sched/os_start.c23
-rw-r--r--nuttx/sched/pthread_create.c74
-rw-r--r--nuttx/sched/pthread_join.c2
-rw-r--r--nuttx/sched/sched_getfiles.c7
-rw-r--r--nuttx/sched/sched_getsockets.c7
-rw-r--r--nuttx/sched/sched_getstreams.c7
-rw-r--r--nuttx/sched/sched_releasetcb.c17
-rw-r--r--nuttx/sched/sched_waitid.c149
-rw-r--r--nuttx/sched/sched_waitpid.c167
-rw-r--r--nuttx/sched/sig_action.c27
-rw-r--r--nuttx/sched/task_create.c41
-rw-r--r--nuttx/sched/task_exithook.c318
-rw-r--r--nuttx/sched/task_init.c66
-rw-r--r--nuttx/sched/task_posixspawn.c1
-rw-r--r--nuttx/sched/task_reparent.c177
-rw-r--r--nuttx/sched/task_setup.c58
-rw-r--r--nuttx/sched/task_start.c9
-rw-r--r--nuttx/sched/task_starthook.c (renamed from nuttx/sched/sched_releasefiles.c)92
-rw-r--r--nuttx/sched/task_vfork.c9
-rw-r--r--nuttx/sched/timer_initialize.c2
-rw-r--r--nuttx/tools/mkconfig.c22
224 files changed, 8651 insertions, 9460 deletions
diff --git a/ROMFS/logging/logconv.m b/ROMFS/logging/logconv.m
index c405410de..5ea2aeb95 100755
--- a/ROMFS/logging/logconv.m
+++ b/ROMFS/logging/logconv.m
@@ -65,10 +65,9 @@ logFormat{17} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, '
logFormat{18} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{19} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
logFormat{20} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
-logFormat{21} = struct('name', 'omnidirectional_flow', 'bytes', 4, 'array', 22,'precision', 'float', 'machineformat', 'ieee-le');
-logFormat{22} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
-logFormat{23} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
-logFormat{24} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{21} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{22} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
+logFormat{23} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
% First get length of one line
columns = length(logFormat);
diff --git a/ROMFS/scripts/rc.FMU_quad_x b/ROMFS/scripts/rc.FMU_quad_x
index d9c9a8457..8787443ea 100644
--- a/ROMFS/scripts/rc.FMU_quad_x
+++ b/ROMFS/scripts/rc.FMU_quad_x
@@ -1,40 +1,67 @@
+#!nsh
+#
+# Flight startup script for PX4FMU with PWM outputs.
+#
+
+# Disable the USB interface
+set USB no
+
+# Disable autostarting other apps
+set MODE custom
+
+echo "[init] doing PX4FMU Quad startup..."
+
+#
+# Start the ORB
#
-# Startup for X-quad on FMU1.5/1.6
-#
-
-echo "[init] uORB"
uorb start
-
-echo "[init] eeprom"
-eeprom start
-if [ -f /eeprom/parameters ]
+
+#
+# Load microSD params
+#
+echo "[init] loading microSD params"
+param select /fs/microsd/parameters
+if [ -f /fs/microsd/parameters ]
then
- param load
+ param load /fs/microsd/parameters
fi
-
-echo "[init] sensors"
-#bma180 start
-#l3gd20 start
-mpu6000 start
-hmc5883 start
-ms5611 start
-
-sensors start
-
-echo "[init] mavlink"
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 2
+
+#
+# Start MAVLink
+#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
-
-echo "[init] commander"
+
+#
+# Start the sensors and test them.
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start the commander.
+#
commander start
-
-echo "[init] attitude control"
+
+#
+# Start the attitude estimator
+#
attitude_estimator_ekf start
-multirotor_att_control start
-
+
echo "[init] starting PWM output"
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
echo "[init] startup done, exiting"
-exit
+exit \ No newline at end of file
diff --git a/ROMFS/scripts/rc.PX4IO b/ROMFS/scripts/rc.PX4IO
index 84e181a5a..1e3963b9a 100644
--- a/ROMFS/scripts/rc.PX4IO
+++ b/ROMFS/scripts/rc.PX4IO
@@ -1,73 +1,80 @@
#!nsh
-
+
+# Disable USB and autostart
set USB no
-
+set MODE camflyer
+
#
-# Start the object request broker
+# Start the ORB
#
uorb start
-
+
#
-# Init the EEPROM
+# Load microSD params
#
-echo "[init] eeprom"
-eeprom start
-if [ -f /eeprom/parameters ]
+echo "[init] loading microSD params"
+param select /fs/microsd/parameters
+if [ -f /fs/microsd/parameters ]
then
- param load
+ param load /fs/microsd/parameters
fi
-
-#
-# Enable / connect to PX4IO
-#
-px4io start
-
+
#
-# Load an appropriate mixer. FMU_pass.mix is a passthru mixer
-# which is good for testing. See ROMFS/mixers for a full list of mixers.
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
#
-mixer load /dev/pwm_output /etc/mixers/FMU_pass.mix
-
+param set MAV_TYPE 1
+
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
-
+
#
-# Start MAVLink on UART1 (dev/ttyS0) at 57600 baud (CLI is now unusable)
+# Start MAVLink
#
-mavlink start -d /dev/ttyS0 -b 57600
+mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
-
+
#
# Start the commander.
#
commander start
-
+
+#
+# Start GPS interface
+#
+gps start
+
#
# Start the attitude estimator
#
-attitude_estimator_ekf start
-
+kalman_demo start
+
#
-# Start the attitude and position controller
+# Start PX4IO interface
#
-fixedwing_att_control start
-fixedwing_pos_control start
-
+px4io start
+
#
-# Start GPS capture. Comment this out if you do not have a GPS.
+# Load mixer and start controllers
#
-gps start
-
+mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
+control_demo start
+
+#
+# Start logging
#
-# Start logging to microSD if we can
-#
-sh /etc/init.d/rc.logging
+sdlog start -s 10
#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
+# Start system state
#
-echo "[init] startup done"
-exit
+if blinkm start
+then
+ echo "using BlinkM for state indication"
+ blinkm systemstate
+else
+ echo "no BlinkM found, OK."
+fi
diff --git a/ROMFS/scripts/rc.PX4IOAR b/ROMFS/scripts/rc.PX4IOAR
index 640cdf541..72df68e35 100644
--- a/ROMFS/scripts/rc.PX4IOAR
+++ b/ROMFS/scripts/rc.PX4IOAR
@@ -17,7 +17,7 @@ echo "[init] doing PX4IOAR startup..."
uorb start
#
-# Load microSD params
+# Init the parameter storage
#
echo "[init] loading microSD params"
param select /fs/microsd/parameters
@@ -27,17 +27,24 @@ then
fi
#
-# Start MAVLink
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
#
-mavlink start -d /dev/ttyS0 -b 57600
-usleep 5000
+param set MAV_TYPE 2
#
-# Start the sensors and test them.
+# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
+# Start MAVLink
+#
+mavlink start -d /dev/ttyS0 -b 57600
+usleep 5000
+
+#
# Start the commander.
#
commander start
@@ -63,14 +70,25 @@ multirotor_att_control start
ardrone_interface start -d /dev/ttyS1
#
+# Start GPS capture
+#
+gps start
+
+#
# Start logging
#
-#sdlog start
-
+sdlog start -s 10
+
#
-# Start GPS capture
+# Start system state
#
-gps start
+if blinkm start
+then
+ echo "using BlinkM for state indication"
+ blinkm systemstate
+else
+ echo "no BlinkM found, OK."
+fi
#
# startup is done; we don't want the shell because we
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index bcc0ac172..05cd6176a 100644
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -434,7 +434,7 @@
tests will now use a relative path to the program and expect the binfmt/
logic to find the absolute path to the program using the PATH variable.
-6.25 2013-xx-xx Gregory Nutt <gnutt@nuttx.org>
+6.25 2013-02-01 Gregory Nutt <gnutt@nuttx.org>
* Makefiles: Removed dependency of distclean on clean in most top-level
files. It makes sense for 'leaf' Makefiles to have this dependency,
@@ -461,7 +461,7 @@
the USB HID keyboard report data.
* apps/examples/wlan: Remove non-functional example.
* apps/examples/ostest/vfork.c: Added a test of vfork().
- * apps/exampes/posix_spawn: Added a test of poxis_spawn().
+ * apps/exampes/posix_spawn: Added a test of posix_spawn().
* apps/examples/ostest: Extend signal handler test to catch
death-of-child signals (SIGCHLD).
* apps/examples/ostest/waitpid.c: Add a test for waitpid(), waitid(),
@@ -478,7 +478,7 @@
* apps/include/builtin.h: Some of the content of
apps/include/apps.h moved to include/nuttx/binfmt/builtin.h.
apps/include/apps.h renamed builtin.h
- * apps/builtin/exec_builtins.c: Move utility builtin
+ * apps/builtin/exec_builtins.c: Move builtin
utility functions from apps/builtin/exec_builtins.c to
binfmt/libbuiltin/libbuiltin_utils.c
* apps/nshlib/nsh_mountcmds.c: The block driver/source
@@ -492,3 +492,18 @@
the entrypoint. Should be ftpd_main (from Yan T.)
* apps/netutils/telnetd/telnetd_driver: Was stuck in a loop if
recv[from]() ever returned a value <= 0.
+ * apps/examples/nettest and poll: Complete Kconfig files.
+ * apps/examples/ostest/waitpid.c: Need to use WEXITSTATUS()
+ to decode the correct exit status.
+ * apps/system/usbmonitor: A daemon that can be used to monitor USB
+ trace outpout.
+ * apps/nshlib/nsh_usbdev.c, nsh_consolemain.c, nsh_session.c, nsh_script.c:
+ Add support for a login script. The init.d/rcS script will be executed
+ once when NSH starts; the .nshrc script will be executed for each session:
+ Once for serial, once for each USB connection, once for each Telnet
+ session.
+ * apps/system/readline: Correct readline() return value. Was not
+ any returning special values when end-of-file or read errors
+ occur (it would return an empty string which is not very useful).
+
+6.26 2013-xx-xx Gregory Nutt <gnutt@nuttx.org>
diff --git a/apps/builtin/exec_builtin.c b/apps/builtin/exec_builtin.c
index 60e8b742d..5d3a1c08a 100644
--- a/apps/builtin/exec_builtin.c
+++ b/apps/builtin/exec_builtin.c
@@ -309,7 +309,7 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
{
struct sched_param param;
pid_t proxy;
- int errcode;
+ int errcode = OK;
#ifdef CONFIG_SCHED_WAITPID
int status;
#endif
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 333dcca3e..3996572cf 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -1465,9 +1465,6 @@ int commander_thread_main(int argc, char *argv[])
} else {
current_status.flag_external_manual_override_ok = true;
}
-
- } else {
- warnx("ARMED, rejecting sys type change\n");
}
}
@@ -1684,12 +1681,13 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
/* check for first, long-term and valid GPS lock -> set home position */
- float hdop_m = gps_position.eph / 100.0f;
- float vdop_m = gps_position.epv / 100.0f;
+ float hdop_m = gps_position.eph_m;
+ float vdop_m = gps_position.epv_m;
/* check if gps fix is ok */
// XXX magic number
- float dop_threshold_m = 2.0f;
+ float hdop_threshold_m = 4.0f;
+ float vdop_threshold_m = 8.0f;
/*
* If horizontal dilution of precision (hdop / eph)
@@ -1700,10 +1698,12 @@ int commander_thread_main(int argc, char *argv[])
* the system is currently not armed, set home
* position to the current position.
*/
- if (gps_position.fix_type == GPS_FIX_TYPE_3D && (hdop_m < dop_threshold_m)
- && (vdop_m < dop_threshold_m)
+
+ if (gps_position.fix_type == GPS_FIX_TYPE_3D
+ && (hdop_m < hdop_threshold_m)
+ && (vdop_m < vdop_threshold_m)
&& !home_position_set
- && (hrt_absolute_time() - gps_position.timestamp < 2000000)
+ && (hrt_absolute_time() - gps_position.timestamp_position < 2000000)
&& !current_status.flag_system_armed) {
warnx("setting home position");
@@ -1712,11 +1712,11 @@ int commander_thread_main(int argc, char *argv[])
home.lon = gps_position.lon;
home.alt = gps_position.alt;
- home.eph = gps_position.eph;
- home.epv = gps_position.epv;
+ home.eph_m = gps_position.eph_m;
+ home.epv_m = gps_position.epv_m;
- home.s_variance = gps_position.s_variance;
- home.p_variance = gps_position.p_variance;
+ home.s_variance_m_s = gps_position.s_variance_m_s;
+ home.p_variance_m = gps_position.p_variance_m;
/* announce new home position */
if (home_pub > 0) {
diff --git a/apps/drivers/boards/px4fmu/px4fmu_init.c b/apps/drivers/boards/px4fmu/px4fmu_init.c
index e88d2861e..9960c6bbd 100644
--- a/apps/drivers/boards/px4fmu/px4fmu_init.c
+++ b/apps/drivers/boards/px4fmu/px4fmu_init.c
@@ -79,13 +79,13 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_lowprintf(__VA_ARGS__)
+# define message(...) lowsyslog(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_lowprintf
+# define message lowsyslog
# else
# define message printf
# endif
diff --git a/apps/drivers/drv_gps.h b/apps/drivers/drv_gps.h
new file mode 100644
index 000000000..1dda8ef0b
--- /dev/null
+++ b/apps/drivers/drv_gps.h
@@ -0,0 +1,70 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file GPS driver interface.
+ */
+
+#ifndef _DRV_GPS_H
+#define _DRV_GPS_H
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+#include "drv_sensor.h"
+#include "drv_orb_dev.h"
+
+#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
+
+#define GPS_DEVICE_PATH "/dev/gps"
+
+typedef enum {
+ GPS_DRIVER_MODE_NONE = 0,
+ GPS_DRIVER_MODE_UBX,
+ GPS_DRIVER_MODE_MTK,
+ GPS_DRIVER_MODE_NMEA,
+} gps_driver_mode_t;
+
+
+/*
+ * ObjDev tag for GPS data.
+ */
+ORB_DECLARE(gps);
+
+/*
+ * ioctl() definitions
+ */
+#define _GPSIOCBASE (0x2800) //TODO: arbitrary choice...
+#define _GPSIOC(_n) (_IOC(_GPSIOCBASE, _n))
+
+#endif /* _DRV_GPS_H */
diff --git a/apps/gps/Makefile b/apps/drivers/gps/Makefile
index 7aaaf50cb..3859a88a5 100644
--- a/apps/gps/Makefile
+++ b/apps/drivers/gps/Makefile
@@ -32,28 +32,11 @@
############################################################################
#
-# Makefile to build the GPS receiver application
+# GPS driver
#
APPNAME = gps
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
-CSRCS = gps.c \
- ubx.c \
- mtk.c \
- nmea_helper.c \
- nmealib/context.c \
- nmealib/generate.c \
- nmealib/generator.c \
- nmealib/gmath.c \
- nmealib/info.c \
- nmealib/parse.c \
- nmealib/parser.c \
- nmealib/sentence.c \
- nmealib/time.c \
- nmealib/tok.c
-
-INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
-
include $(APPDIR)/mk/app.mk
diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp
new file mode 100644
index 000000000..6d7cfcc68
--- /dev/null
+++ b/apps/drivers/gps/gps.cpp
@@ -0,0 +1,536 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gps.cpp
+ * Driver for the GPS on a serial port
+ */
+
+#include <nuttx/clock.h>
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/device/i2c.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/scheduling_priorities.h>
+#include <systemlib/err.h>
+#include <drivers/drv_gps.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_gps_position.h>
+
+#include "ubx.h"
+#include "mtk.h"
+
+
+#define TIMEOUT_5HZ 400
+#define RATE_MEASUREMENT_PERIOD 5000000
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+
+
+class GPS : public device::CDev
+{
+public:
+ GPS(const char* uart_path);
+ ~GPS();
+
+ virtual int init();
+
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+private:
+
+ bool _task_should_exit; ///< flag to make the main worker task exit
+ int _serial_fd; ///< serial interface to GPS
+ unsigned _baudrate; ///< current baudrate
+ char _port[20]; ///< device / serial port path
+ volatile int _task; //< worker task
+ bool _healthy; ///< flag to signal if the GPS is ok
+ bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed
+ bool _mode_changed; ///< flag that the GPS mode has changed
+ gps_driver_mode_t _mode; ///< current mode
+ GPS_Helper *_Helper; ///< instance of GPS parser
+ struct vehicle_gps_position_s _report; ///< uORB topic for gps position
+ orb_advert_t _report_pub; ///< uORB pub for gps position
+ float _rate; ///< position update rate
+
+
+ /**
+ * Try to configure the GPS, handle outgoing communication to the GPS
+ */
+ void config();
+
+ /**
+ * Trampoline to the worker task
+ */
+ static void task_main_trampoline(void *arg);
+
+
+ /**
+ * Worker task: main GPS thread that configures the GPS and parses incoming data, always running
+ */
+ void task_main(void);
+
+ /**
+ * Set the baudrate of the UART to the GPS
+ */
+ int set_baudrate(unsigned baud);
+
+ /**
+ * Send a reset command to the GPS
+ */
+ void cmd_reset();
+
+};
+
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int gps_main(int argc, char *argv[]);
+
+namespace
+{
+
+GPS *g_dev;
+
+}
+
+
+GPS::GPS(const char* uart_path) :
+ CDev("gps", GPS_DEVICE_PATH),
+ _task_should_exit(false),
+ _healthy(false),
+ _mode_changed(false),
+ _mode(GPS_DRIVER_MODE_UBX),
+ _Helper(nullptr),
+ _report_pub(-1),
+ _rate(0.0f)
+{
+ /* store port name */
+ strncpy(_port, uart_path, sizeof(_port));
+ /* enforce null termination */
+ _port[sizeof(_port) - 1] = '\0';
+
+ /* we need this potentially before it could be set in task_main */
+ g_dev = this;
+ memset(&_report, 0, sizeof(_report));
+
+ _debug_enabled = true;
+}
+
+GPS::~GPS()
+{
+ /* tell the task we want it to go away */
+ _task_should_exit = true;
+
+ /* spin waiting for the task to stop */
+ for (unsigned i = 0; (i < 10) && (_task != -1); i++) {
+ /* give it another 100ms */
+ usleep(100000);
+ }
+
+ /* well, kill it anyway, though this will probably crash */
+ if (_task != -1)
+ task_delete(_task);
+ g_dev = nullptr;
+
+}
+
+int
+GPS::init()
+{
+ int ret = ERROR;
+
+ /* do regular cdev init */
+ if (CDev::init() != OK)
+ goto out;
+
+ /* start the GPS driver worker task */
+ _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
+
+ if (_task < 0) {
+ warnx("task start failed: %d", errno);
+ return -errno;
+ }
+
+ ret = OK;
+out:
+ return ret;
+}
+
+int
+GPS::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ lock();
+
+ int ret = OK;
+
+ switch (cmd) {
+ case SENSORIOCRESET:
+ cmd_reset();
+ break;
+ }
+
+ unlock();
+
+ return ret;
+}
+
+void
+GPS::task_main_trampoline(void *arg)
+{
+ g_dev->task_main();
+}
+
+void
+GPS::task_main()
+{
+ log("starting");
+
+ /* open the serial port */
+ _serial_fd = ::open(_port, O_RDWR);
+
+ if (_serial_fd < 0) {
+ log("failed to open serial port: %s err: %d", _port, errno);
+ /* tell the dtor that we are exiting, set error code */
+ _task = -1;
+ _exit(1);
+ }
+
+ uint64_t last_rate_measurement = hrt_absolute_time();
+ unsigned last_rate_count = 0;
+
+ /* loop handling received serial bytes and also configuring in between */
+ while (!_task_should_exit) {
+
+ if (_Helper != nullptr) {
+ delete(_Helper);
+ /* set to zero to ensure parser is not used while not instantiated */
+ _Helper = nullptr;
+ }
+
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ _Helper = new UBX(_serial_fd, &_report);
+ break;
+ case GPS_DRIVER_MODE_MTK:
+ _Helper = new MTK(_serial_fd, &_report);
+ break;
+ case GPS_DRIVER_MODE_NMEA:
+ //_Helper = new NMEA(); //TODO: add NMEA
+ break;
+ default:
+ break;
+ }
+ unlock();
+ if (_Helper->configure(_baudrate) == 0) {
+ unlock();
+ while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
+// lock();
+ /* opportunistic publishing - else invalid data would end up on the bus */
+ if (_report_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ } else {
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ }
+
+ last_rate_count++;
+
+ /* measure update rate every 5 seconds */
+ if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
+ _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f);
+ last_rate_measurement = hrt_absolute_time();
+ last_rate_count = 0;
+ }
+
+ if (!_healthy) {
+ warnx("module found");
+ _healthy = true;
+ }
+ }
+ if (_healthy) {
+ warnx("module lost");
+ _healthy = false;
+ _rate = 0.0f;
+ }
+
+ lock();
+ }
+ lock();
+
+ /* select next mode */
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ _mode = GPS_DRIVER_MODE_MTK;
+ break;
+ case GPS_DRIVER_MODE_MTK:
+ _mode = GPS_DRIVER_MODE_UBX;
+ break;
+ // case GPS_DRIVER_MODE_NMEA:
+ // _mode = GPS_DRIVER_MODE_UBX;
+ // break;
+ default:
+ break;
+ }
+
+ }
+ debug("exiting");
+
+ ::close(_serial_fd);
+
+ /* tell the dtor that we are exiting */
+ _task = -1;
+ _exit(0);
+}
+
+
+
+void
+GPS::cmd_reset()
+{
+ //XXX add reset?
+}
+
+void
+GPS::print_info()
+{
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ warnx("protocol: UBX");
+ break;
+ case GPS_DRIVER_MODE_MTK:
+ warnx("protocol: MTK");
+ break;
+ case GPS_DRIVER_MODE_NMEA:
+ warnx("protocol: NMEA");
+ break;
+ default:
+ break;
+ }
+ warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
+ if (_report.timestamp_position != 0) {
+ warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type,
+ (double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f));
+ warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
+ warnx("update rate: %6.2f Hz", (double)_rate);
+ }
+
+ usleep(100000);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace gps
+{
+
+GPS *g_dev;
+
+void start(const char *uart_path);
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start(const char *uart_path)
+{
+ int fd;
+
+ if (g_dev != nullptr)
+ errx(1, "already started");
+
+ /* create the driver */
+ g_dev = new GPS(uart_path);
+
+ if (g_dev == nullptr)
+ goto fail;
+
+ if (OK != g_dev->init())
+ goto fail;
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(GPS_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ errx(1, "Could not open device path: %s\n", GPS_DEVICE_PATH);
+ goto fail;
+ }
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver.
+ */
+void
+stop()
+{
+ delete g_dev;
+ g_dev = nullptr;
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(GPS_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ err(1, "failed ");
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ err(1, "driver reset failed");
+
+ exit(0);
+}
+
+/**
+ * Print the status of the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running");
+
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+
+int
+gps_main(int argc, char *argv[])
+{
+
+ /* set to default */
+ char* device_name = GPS_DEFAULT_UART_PORT;
+
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start")) {
+ /* work around getopt unreliability */
+ if (argc > 3) {
+ if (!strcmp(argv[2], "-d")) {
+ device_name = argv[3];
+ } else {
+ goto out;
+ }
+ }
+ gps::start(device_name);
+ }
+
+ if (!strcmp(argv[1], "stop"))
+ gps::stop();
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test"))
+ gps::test();
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset"))
+ gps::reset();
+
+ /*
+ * Print driver status.
+ */
+ if (!strcmp(argv[1], "status"))
+ gps::info();
+
+out:
+ errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n]");
+}
diff --git a/apps/drivers/gps/gps_helper.cpp b/apps/drivers/gps/gps_helper.cpp
new file mode 100644
index 000000000..9c1fad569
--- /dev/null
+++ b/apps/drivers/gps/gps_helper.cpp
@@ -0,0 +1,92 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 PX4 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 <termios.h>
+#include <errno.h>
+#include <systemlib/err.h>
+#include "gps_helper.h"
+
+/* @file gps_helper.cpp */
+
+int
+GPS_Helper::set_baudrate(const int &fd, unsigned baud)
+{
+ /* process baud rate */
+ int speed;
+
+ switch (baud) {
+ case 9600: speed = B9600; break;
+
+ case 19200: speed = B19200; break;
+
+ case 38400: speed = B38400; break;
+
+ case 57600: speed = B57600; break;
+
+ case 115200: speed = B115200; break;
+
+ warnx("try baudrate: %d\n", speed);
+
+ default:
+ warnx("ERROR: Unsupported baudrate: %d\n", baud);
+ return -EINVAL;
+ }
+ struct termios uart_config;
+ int termios_state;
+
+ /* fill the struct for the new configuration */
+ tcgetattr(fd, &uart_config);
+
+ /* clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
+ /* no parity, one stop bit */
+ uart_config.c_cflag &= ~(CSTOPB | PARENB);
+
+ /* set baud rate */
+ if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
+ warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state);
+ return -1;
+ }
+ if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
+ warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state);
+ return -1;
+ }
+ if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
+ warnx("ERROR setting baudrate (tcsetattr)\n");
+ return -1;
+ }
+ /* XXX if resetting the parser here, ensure it does exist (check for null pointer) */
+ return 0;
+}
diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h
new file mode 100644
index 000000000..f3d3bc40b
--- /dev/null
+++ b/apps/drivers/gps/gps_helper.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/* @file gps_helper.h */
+
+#ifndef GPS_HELPER_H
+#define GPS_HELPER_H
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_gps_position.h>
+
+class GPS_Helper
+{
+public:
+ virtual int configure(unsigned &baud) = 0;
+ virtual int receive(unsigned timeout) = 0;
+ int set_baudrate(const int &fd, unsigned baud);
+};
+
+#endif /* GPS_HELPER_H */
diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp
new file mode 100644
index 000000000..4762bd503
--- /dev/null
+++ b/apps/drivers/gps/mtk.cpp
@@ -0,0 +1,274 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/* @file mkt.cpp */
+
+#include <unistd.h>
+#include <stdio.h>
+#include <poll.h>
+#include <math.h>
+#include <string.h>
+#include <assert.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+
+#include "mtk.h"
+
+
+MTK::MTK(const int &fd, struct vehicle_gps_position_s *gps_position) :
+_fd(fd),
+_gps_position(gps_position),
+_mtk_revision(0)
+{
+ decode_init();
+}
+
+MTK::~MTK()
+{
+}
+
+int
+MTK::configure(unsigned &baudrate)
+{
+ /* set baudrate first */
+ if (GPS_Helper::set_baudrate(_fd, MTK_BAUDRATE) != 0)
+ return -1;
+
+ baudrate = MTK_BAUDRATE;
+
+ /* Write config messages, don't wait for an answer */
+ if (strlen(MTK_OUTPUT_5HZ) != write(_fd, MTK_OUTPUT_5HZ, strlen(MTK_OUTPUT_5HZ))) {
+ warnx("mtk: config write failed");
+ return -1;
+ }
+ usleep(10000);
+
+ if (strlen(MTK_SET_BINARY) != write(_fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) {
+ warnx("mtk: config write failed");
+ return -1;
+ }
+ usleep(10000);
+
+ if (strlen(SBAS_ON) != write(_fd, SBAS_ON, strlen(SBAS_ON))) {
+ warnx("mtk: config write failed");
+ return -1;
+ }
+ usleep(10000);
+
+ if (strlen(WAAS_ON) != write(_fd, WAAS_ON, strlen(WAAS_ON))) {
+ warnx("mtk: config write failed");
+ return -1;
+ }
+ usleep(10000);
+
+ if (strlen(MTK_NAVTHRES_OFF) != write(_fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) {
+ warnx("mtk: config write failed");
+ return -1;
+ }
+
+ return 0;
+}
+
+int
+MTK::receive(unsigned timeout)
+{
+ /* poll descriptor */
+ pollfd fds[1];
+ fds[0].fd = _fd;
+ fds[0].events = POLLIN;
+
+ uint8_t buf[32];
+ gps_mtk_packet_t packet;
+
+ /* timeout additional to poll */
+ uint64_t time_started = hrt_absolute_time();
+
+ int j = 0;
+ ssize_t count = 0;
+
+ while (true) {
+
+ /* first read whatever is left */
+ if (j < count) {
+ /* pass received bytes to the packet decoder */
+ while (j < count) {
+ if (parse_char(buf[j], packet) > 0) {
+ handle_message(packet);
+ return 1;
+ }
+ /* in case we keep trying but only get crap from GPS */
+ if (time_started + timeout*1000 < hrt_absolute_time() ) {
+ return -1;
+ }
+ j++;
+ }
+ /* everything is read */
+ j = count = 0;
+ }
+
+ /* then poll for new data */
+ int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout);
+
+ if (ret < 0) {
+ /* something went wrong when polling */
+ return -1;
+
+ } else if (ret == 0) {
+ /* Timeout */
+ return -1;
+
+ } else if (ret > 0) {
+ /* if we have new data from GPS, go handle it */
+ if (fds[0].revents & POLLIN) {
+ /*
+ * We are here because poll says there is some data, so this
+ * won't block even on a blocking device. If more bytes are
+ * available, we'll go back to poll() again...
+ */
+ count = ::read(_fd, buf, sizeof(buf));
+ }
+ }
+ }
+}
+
+void
+MTK::decode_init(void)
+{
+ _rx_ck_a = 0;
+ _rx_ck_b = 0;
+ _rx_count = 0;
+ _decode_state = MTK_DECODE_UNINIT;
+}
+int
+MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
+{
+ int ret = 0;
+
+ if (_decode_state == MTK_DECODE_UNINIT) {
+
+ if (b == MTK_SYNC1_V16) {
+ _decode_state = MTK_DECODE_GOT_CK_A;
+ _mtk_revision = 16;
+ } else if (b == MTK_SYNC1_V19) {
+ _decode_state = MTK_DECODE_GOT_CK_A;
+ _mtk_revision = 19;
+ }
+
+ } else if (_decode_state == MTK_DECODE_GOT_CK_A) {
+ if (b == MTK_SYNC2) {
+ _decode_state = MTK_DECODE_GOT_CK_B;
+
+ } else {
+ // Second start symbol was wrong, reset state machine
+ decode_init();
+ }
+
+ } else if (_decode_state == MTK_DECODE_GOT_CK_B) {
+ // Add to checksum
+ if (_rx_count < 33)
+ add_byte_to_checksum(b);
+
+ // Fill packet buffer
+ ((uint8_t*)(&packet))[_rx_count] = b;
+ _rx_count++;
+
+ /* Packet size minus checksum, XXX ? */
+ if (_rx_count >= sizeof(packet)) {
+ /* Compare checksum */
+ if (_rx_ck_a == packet.ck_a && _rx_ck_b == packet.ck_b) {
+ ret = 1;
+ } else {
+ warnx("MTK Checksum invalid");
+ ret = -1;
+ }
+ // Reset state machine to decode next packet
+ decode_init();
+ }
+ }
+ return ret;
+}
+
+void
+MTK::handle_message(gps_mtk_packet_t &packet)
+{
+ if (_mtk_revision == 16) {
+ _gps_position->lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7
+ _gps_position->lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7
+ } else if (_mtk_revision == 19) {
+ _gps_position->lat = packet.latitude; // both degrees*1e7
+ _gps_position->lon = packet.longitude; // both degrees*1e7
+ } else {
+ warnx("mtk: unknown revision");
+ _gps_position->lat = 0;
+ _gps_position->lon = 0;
+ }
+ _gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
+ _gps_position->fix_type = packet.fix_type;
+ _gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
+ _gps_position->epv_m = 0.0; //unknown in mtk custom mode
+ _gps_position->vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s
+ _gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
+ _gps_position->satellites_visible = packet.satellites;
+
+ /* convert time and date information to unix timestamp */
+ struct tm timeinfo; //TODO: test this conversion
+ uint32_t timeinfo_conversion_temp;
+
+ timeinfo.tm_mday = packet.date * 1e-4;
+ timeinfo_conversion_temp = packet.date - timeinfo.tm_mday * 1e4;
+ timeinfo.tm_mon = timeinfo_conversion_temp * 1e-2 - 1;
+ timeinfo.tm_year = (timeinfo_conversion_temp - (timeinfo.tm_mon + 1) * 1e2) + 100;
+
+ timeinfo.tm_hour = packet.utc_time * 1e-7;
+ timeinfo_conversion_temp = packet.utc_time - timeinfo.tm_hour * 1e7;
+ timeinfo.tm_min = timeinfo_conversion_temp * 1e-5;
+ timeinfo_conversion_temp -= timeinfo.tm_min * 1e5;
+ timeinfo.tm_sec = timeinfo_conversion_temp * 1e-3;
+ timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3;
+ time_t epoch = mktime(&timeinfo);
+
+ _gps_position->time_gps_usec = epoch * 1e6; //TODO: test this
+ _gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3;
+ _gps_position->timestamp_position = _gps_position->timestamp_time = hrt_absolute_time();
+
+ return;
+}
+
+void
+MTK::add_byte_to_checksum(uint8_t b)
+{
+ _rx_ck_a = _rx_ck_a + b;
+ _rx_ck_b = _rx_ck_b + _rx_ck_a;
+}
diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h
new file mode 100644
index 000000000..d4e390b01
--- /dev/null
+++ b/apps/drivers/gps/mtk.h
@@ -0,0 +1,124 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/* @file mtk.h */
+
+#ifndef MTK_H_
+#define MTK_H_
+
+#include "gps_helper.h"
+
+#define MTK_SYNC1_V16 0xd0
+#define MTK_SYNC1_V19 0xd1
+#define MTK_SYNC2 0xdd
+
+#define MTK_OUTPUT_5HZ "$PMTK220,200*2C\r\n"
+#define MTK_SET_BINARY "$PGCMD,16,0,0,0,0,0*6A\r\n"
+#define SBAS_ON "$PMTK313,1*2E\r\n"
+#define WAAS_ON "$PMTK301,2*2E\r\n"
+#define MTK_NAVTHRES_OFF "$PMTK397,0*23\r\n"
+
+#define MTK_TIMEOUT_5HZ 400
+#define MTK_BAUDRATE 38400
+
+typedef enum {
+ MTK_DECODE_UNINIT = 0,
+ MTK_DECODE_GOT_CK_A = 1,
+ MTK_DECODE_GOT_CK_B = 2
+} mtk_decode_state_t;
+
+/** the structures of the binary packets */
+#pragma pack(push, 1)
+
+typedef struct {
+ uint8_t payload; ///< Number of payload bytes
+ int32_t latitude; ///< Latitude in degrees * 10^7
+ int32_t longitude; ///< Longitude in degrees * 10^7
+ uint32_t msl_altitude; ///< MSL altitude in meters * 10^2
+ uint32_t ground_speed; ///< velocity in m/s
+ int32_t heading; ///< heading in degrees * 10^2
+ uint8_t satellites; ///< number of sattelites used
+ uint8_t fix_type; ///< fix type: XXX correct for that
+ uint32_t date;
+ uint32_t utc_time;
+ uint16_t hdop; ///< horizontal dilution of position (without unit)
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_mtk_packet_t;
+
+#pragma pack(pop)
+
+#define MTK_RECV_BUFFER_SIZE 40
+
+class MTK : public GPS_Helper
+{
+public:
+ MTK(const int &fd, struct vehicle_gps_position_s *gps_position);
+ ~MTK();
+ int receive(unsigned timeout);
+ int configure(unsigned &baudrate);
+
+private:
+ /**
+ * Parse the binary MTK packet
+ */
+ int parse_char(uint8_t b, gps_mtk_packet_t &packet);
+
+ /**
+ * Handle the package once it has arrived
+ */
+ void handle_message(gps_mtk_packet_t &packet);
+
+ /**
+ * Reset the parse state machine for a fresh start
+ */
+ void decode_init(void);
+
+ /**
+ * While parsing add every byte (except the sync bytes) to the checksum
+ */
+ void add_byte_to_checksum(uint8_t);
+
+ int _fd;
+ struct vehicle_gps_position_s *_gps_position;
+ mtk_decode_state_t _decode_state;
+ uint8_t _mtk_revision;
+ uint8_t _rx_buffer[MTK_RECV_BUFFER_SIZE];
+ unsigned _rx_count;
+ uint8_t _rx_ck_a;
+ uint8_t _rx_ck_b;
+};
+
+#endif /* MTK_H_ */
diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp
new file mode 100644
index 000000000..74cbc5aaf
--- /dev/null
+++ b/apps/drivers/gps/ubx.cpp
@@ -0,0 +1,745 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/* @file U-Blox protocol implementation */
+
+#include <unistd.h>
+#include <stdio.h>
+#include <poll.h>
+#include <math.h>
+#include <string.h>
+#include <assert.h>
+#include <systemlib/err.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <drivers/drv_hrt.h>
+
+#include "ubx.h"
+
+#define UBX_CONFIG_TIMEOUT 100
+
+UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
+_fd(fd),
+_gps_position(gps_position),
+_waiting_for_ack(false)
+{
+ decode_init();
+}
+
+UBX::~UBX()
+{
+}
+
+int
+UBX::configure(unsigned &baudrate)
+{
+ _waiting_for_ack = true;
+
+ /* try different baudrates */
+ const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
+
+ for (int baud_i = 0; baud_i < 5; baud_i++) {
+ baudrate = baudrates_to_try[baud_i];
+ set_baudrate(_fd, baudrate);
+
+ /* Send a CFG-PRT message to set the UBX protocol for in and out
+ * and leave the baudrate as it is, we just want an ACK-ACK from this
+ */
+ type_gps_bin_cfg_prt_packet_t cfg_prt_packet;
+ /* Set everything else of the packet to 0, otherwise the module wont accept it */
+ memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet));
+
+ _clsID_needed = UBX_CLASS_CFG;
+ _msgID_needed = UBX_MESSAGE_CFG_PRT;
+
+ /* Define the package contents, don't change the baudrate */
+ cfg_prt_packet.clsID = UBX_CLASS_CFG;
+ cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
+ cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
+ cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
+ cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
+ cfg_prt_packet.baudRate = baudrate;
+ cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
+ cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
+
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ /* Send a CFG-PRT message again, this time change the baudrate */
+
+ cfg_prt_packet.clsID = UBX_CLASS_CFG;
+ cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
+ cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
+ cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
+ cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
+ cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
+ cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
+ cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
+ if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
+ set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
+ baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
+ }
+
+ /* no ack is ecpected here, keep going configuring */
+
+ /* send a CFT-RATE message to define update rate */
+ type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
+ memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
+
+ _clsID_needed = UBX_CLASS_CFG;
+ _msgID_needed = UBX_MESSAGE_CFG_RATE;
+
+ cfg_rate_packet.clsID = UBX_CLASS_CFG;
+ cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE;
+ cfg_rate_packet.length = UBX_CFG_RATE_LENGTH;
+ cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASRATE;
+ cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE;
+ cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ /* send a NAV5 message to set the options for the internal filter */
+ type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet;
+ memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet));
+
+ _clsID_needed = UBX_CLASS_CFG;
+ _msgID_needed = UBX_MESSAGE_CFG_NAV5;
+
+ cfg_nav5_packet.clsID = UBX_CLASS_CFG;
+ cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5;
+ cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH;
+ cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK;
+ cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL;
+ cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ type_gps_bin_cfg_msg_packet_t cfg_msg_packet;
+ memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet));
+
+ _clsID_needed = UBX_CLASS_CFG;
+ _msgID_needed = UBX_MESSAGE_CFG_MSG;
+
+ cfg_msg_packet.clsID = UBX_CLASS_CFG;
+ cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG;
+ cfg_msg_packet.length = UBX_CFG_MSG_LENGTH;
+ /* Choose fast 5Hz rate for all messages except SVINFO which is big and not important */
+ cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_5HZ;
+
+ cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
+ cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
+ cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
+ cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO;
+ /* For satelites info 1Hz is enough */
+ cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_1HZ;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
+ cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+
+ cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
+ cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED;
+
+ send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet));
+ if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ /* try next baudrate */
+ continue;
+ }
+// cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
+// cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP;
+
+// cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM;
+// cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI;
+
+ _waiting_for_ack = false;
+ return 0;
+ }
+ return -1;
+}
+
+int
+UBX::receive(unsigned timeout)
+{
+ /* poll descriptor */
+ pollfd fds[1];
+ fds[0].fd = _fd;
+ fds[0].events = POLLIN;
+
+ uint8_t buf[32];
+
+ /* timeout additional to poll */
+ uint64_t time_started = hrt_absolute_time();
+
+ int j = 0;
+ ssize_t count = 0;
+
+ while (true) {
+
+ /* pass received bytes to the packet decoder */
+ while (j < count) {
+ if (parse_char(buf[j]) > 0) {
+ /* return to configure during configuration or to the gps driver during normal work
+ * if a packet has arrived */
+ if (handle_message() > 0)
+ return 1;
+ }
+ /* in case we keep trying but only get crap from GPS */
+ if (time_started + timeout*1000 < hrt_absolute_time() ) {
+ return -1;
+ }
+ j++;
+ }
+
+ /* everything is read */
+ j = count = 0;
+
+ /* then poll for new data */
+ int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout);
+
+ if (ret < 0) {
+ /* something went wrong when polling */
+ return -1;
+
+ } else if (ret == 0) {
+ /* Timeout */
+ return -1;
+
+ } else if (ret > 0) {
+ /* if we have new data from GPS, go handle it */
+ if (fds[0].revents & POLLIN) {
+ /*
+ * We are here because poll says there is some data, so this
+ * won't block even on a blocking device. If more bytes are
+ * available, we'll go back to poll() again...
+ */
+ count = ::read(_fd, buf, sizeof(buf));
+ }
+ }
+ }
+}
+
+int
+UBX::parse_char(uint8_t b)
+{
+ switch (_decode_state) {
+ /* First, look for sync1 */
+ case UBX_DECODE_UNINIT:
+ if (b == UBX_SYNC1) {
+ _decode_state = UBX_DECODE_GOT_SYNC1;
+ }
+ break;
+ /* Second, look for sync2 */
+ case UBX_DECODE_GOT_SYNC1:
+ if (b == UBX_SYNC2) {
+ _decode_state = UBX_DECODE_GOT_SYNC2;
+ } else {
+ /* Second start symbol was wrong, reset state machine */
+ decode_init();
+ }
+ break;
+ /* Now look for class */
+ case UBX_DECODE_GOT_SYNC2:
+ /* everything except sync1 and sync2 needs to be added to the checksum */
+ add_byte_to_checksum(b);
+ /* check for known class */
+ switch (b) {
+ case UBX_CLASS_ACK:
+ _decode_state = UBX_DECODE_GOT_CLASS;
+ _message_class = ACK;
+ break;
+
+ case UBX_CLASS_NAV:
+ _decode_state = UBX_DECODE_GOT_CLASS;
+ _message_class = NAV;
+ break;
+
+// case UBX_CLASS_RXM:
+// _decode_state = UBX_DECODE_GOT_CLASS;
+// _message_class = RXM;
+// break;
+
+ case UBX_CLASS_CFG:
+ _decode_state = UBX_DECODE_GOT_CLASS;
+ _message_class = CFG;
+ break;
+ default: //unknown class: reset state machine
+ decode_init();
+ break;
+ }
+ break;
+ case UBX_DECODE_GOT_CLASS:
+ add_byte_to_checksum(b);
+ switch (_message_class) {
+ case NAV:
+ switch (b) {
+ case UBX_MESSAGE_NAV_POSLLH:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = NAV_POSLLH;
+ break;
+
+ case UBX_MESSAGE_NAV_SOL:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = NAV_SOL;
+ break;
+
+ case UBX_MESSAGE_NAV_TIMEUTC:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = NAV_TIMEUTC;
+ break;
+
+// case UBX_MESSAGE_NAV_DOP:
+// _decode_state = UBX_DECODE_GOT_MESSAGEID;
+// _message_id = NAV_DOP;
+// break;
+
+ case UBX_MESSAGE_NAV_SVINFO:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = NAV_SVINFO;
+ break;
+
+ case UBX_MESSAGE_NAV_VELNED:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = NAV_VELNED;
+ break;
+
+ default: //unknown class: reset state machine, should not happen
+ decode_init();
+ break;
+ }
+ break;
+// case RXM:
+// switch (b) {
+// case UBX_MESSAGE_RXM_SVSI:
+// _decode_state = UBX_DECODE_GOT_MESSAGEID;
+// _message_id = RXM_SVSI;
+// break;
+//
+// default: //unknown class: reset state machine, should not happen
+// decode_init();
+// break;
+// }
+// break;
+
+ case CFG:
+ switch (b) {
+ case UBX_MESSAGE_CFG_NAV5:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = CFG_NAV5;
+ break;
+
+ default: //unknown class: reset state machine, should not happen
+ decode_init();
+ break;
+ }
+ break;
+
+ case ACK:
+ switch (b) {
+ case UBX_MESSAGE_ACK_ACK:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = ACK_ACK;
+ break;
+ case UBX_MESSAGE_ACK_NAK:
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _message_id = ACK_NAK;
+ break;
+ default: //unknown class: reset state machine, should not happen
+ decode_init();
+ break;
+ }
+ break;
+ default: //should not happen because we set the class
+ warnx("UBX Error, we set a class that we don't know");
+ decode_init();
+// config_needed = true;
+ break;
+ }
+ break;
+ case UBX_DECODE_GOT_MESSAGEID:
+ add_byte_to_checksum(b);
+ _payload_size = b; //this is the first length byte
+ _decode_state = UBX_DECODE_GOT_LENGTH1;
+ break;
+ case UBX_DECODE_GOT_LENGTH1:
+ add_byte_to_checksum(b);
+ _payload_size += b << 8; // here comes the second byte of length
+ _decode_state = UBX_DECODE_GOT_LENGTH2;
+ break;
+ case UBX_DECODE_GOT_LENGTH2:
+ /* Add to checksum if not yet at checksum byte */
+ if (_rx_count < _payload_size)
+ add_byte_to_checksum(b);
+ _rx_buffer[_rx_count] = b;
+ /* once the payload has arrived, we can process the information */
+ if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes
+
+ /* compare checksum */
+ if (_rx_ck_a == _rx_buffer[_rx_count-1] && _rx_ck_b == _rx_buffer[_rx_count]) {
+ return 1;
+ } else {
+ decode_init();
+ return -1;
+ warnx("ubx: Checksum wrong");
+ }
+
+ return 1;
+ } else if (_rx_count < RECV_BUFFER_SIZE) {
+ _rx_count++;
+ } else {
+ warnx("ubx: buffer full");
+ decode_init();
+ return -1;
+ }
+ break;
+ default:
+ break;
+ }
+ return 0; //XXX ?
+}
+
+
+int
+UBX::handle_message()
+{
+ int ret = 0;
+
+ switch (_message_id) { //this enum is unique for all ids --> no need to check the class
+ case NAV_POSLLH: {
+// printf("GOT NAV_POSLLH MESSAGE\n");
+ if (!_waiting_for_ack) {
+ gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer;
+
+ _gps_position->lat = packet->lat;
+ _gps_position->lon = packet->lon;
+ _gps_position->alt = packet->height_msl;
+
+ _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m
+ _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m
+
+ /* Add timestamp to finish the report */
+ _gps_position->timestamp_position = hrt_absolute_time();
+ /* only return 1 when new position is available */
+ ret = 1;
+ }
+ break;
+ }
+
+ case NAV_SOL: {
+// printf("GOT NAV_SOL MESSAGE\n");
+ if (!_waiting_for_ack) {
+ gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
+
+ _gps_position->fix_type = packet->gpsFix;
+ _gps_position->s_variance_m_s = packet->sAcc;
+ _gps_position->p_variance_m = packet->pAcc;
+
+ _gps_position->timestamp_variance = hrt_absolute_time();
+ }
+ break;
+ }
+
+// case NAV_DOP: {
+//// printf("GOT NAV_DOP MESSAGE\n");
+// gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer;
+//
+// _gps_position->eph_m = packet->hDOP;
+// _gps_position->epv = packet->vDOP;
+//
+// _gps_position->timestamp_posdilution = hrt_absolute_time();
+//
+// _new_nav_dop = true;
+//
+// break;
+// }
+
+ case NAV_TIMEUTC: {
+// printf("GOT NAV_TIMEUTC MESSAGE\n");
+
+ if (!_waiting_for_ack) {
+ gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer;
+
+ //convert to unix timestamp
+ struct tm timeinfo;
+ timeinfo.tm_year = packet->year - 1900;
+ timeinfo.tm_mon = packet->month - 1;
+ timeinfo.tm_mday = packet->day;
+ timeinfo.tm_hour = packet->hour;
+ timeinfo.tm_min = packet->min;
+ timeinfo.tm_sec = packet->sec;
+
+ time_t epoch = mktime(&timeinfo);
+
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
+
+ _gps_position->timestamp_time = hrt_absolute_time();
+ }
+ break;
+ }
+
+ case NAV_SVINFO: {
+// printf("GOT NAV_SVINFO MESSAGE\n");
+
+ if (!_waiting_for_ack) {
+ //this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message
+ const int length_part1 = 8;
+ char _rx_buffer_part1[length_part1];
+ memcpy(_rx_buffer_part1, _rx_buffer, length_part1);
+ gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer_part1;
+
+ //read checksum
+ const int length_part3 = 2;
+ char _rx_buffer_part3[length_part3];
+ memcpy(_rx_buffer_part3, &(_rx_buffer[_rx_count - 1]), length_part3);
+
+ //definitions needed to read numCh elements from the buffer:
+ const int length_part2 = 12;
+ gps_bin_nav_svinfo_part2_packet_t *packet_part2;
+ char _rx_buffer_part2[length_part2]; //for temporal storage
+
+ uint8_t satellites_used = 0;
+ int i;
+
+ for (i = 0; i < packet_part1->numCh; i++) { //for each channel
+
+ /* Get satellite information from the buffer */
+ memcpy(_rx_buffer_part2, &(_rx_buffer[length_part1 + i * length_part2]), length_part2);
+ packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) _rx_buffer_part2;
+
+
+ /* Write satellite information in the global storage */
+ _gps_position->satellite_prn[i] = packet_part2->svid;
+
+ //if satellite information is healthy store the data
+ uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield
+
+ if (!unhealthy) {
+ if ((packet_part2->flags) & 1) { //flags is a bitfield
+ _gps_position->satellite_used[i] = 1;
+ satellites_used++;
+
+ } else {
+ _gps_position->satellite_used[i] = 0;
+ }
+
+ _gps_position->satellite_snr[i] = packet_part2->cno;
+ _gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev);
+ _gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f);
+
+ } else {
+ _gps_position->satellite_used[i] = 0;
+ _gps_position->satellite_snr[i] = 0;
+ _gps_position->satellite_elevation[i] = 0;
+ _gps_position->satellite_azimuth[i] = 0;
+ }
+
+ }
+
+ for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused
+ /* Unused channels have to be set to zero for e.g. MAVLink */
+ _gps_position->satellite_prn[i] = 0;
+ _gps_position->satellite_used[i] = 0;
+ _gps_position->satellite_snr[i] = 0;
+ _gps_position->satellite_elevation[i] = 0;
+ _gps_position->satellite_azimuth[i] = 0;
+ }
+ _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones
+
+ /* set timestamp if any sat info is available */
+ if (packet_part1->numCh > 0) {
+ _gps_position->satellite_info_available = true;
+ } else {
+ _gps_position->satellite_info_available = false;
+ }
+ _gps_position->timestamp_satellites = hrt_absolute_time();
+ }
+
+ break;
+ }
+
+ case NAV_VELNED: {
+// printf("GOT NAV_VELNED MESSAGE\n");
+
+ if (!_waiting_for_ack) {
+ gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
+
+ _gps_position->vel_m_s = (float)packet->speed * 1e-2f;
+ _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f;
+ _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f;
+ _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f;
+ _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->vel_ned_valid = true;
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ }
+
+ break;
+ }
+
+// case RXM_SVSI: {
+// printf("GOT RXM_SVSI MESSAGE\n");
+// const int length_part1 = 7;
+// char _rx_buffer_part1[length_part1];
+// memcpy(_rx_buffer_part1, _rx_buffer, length_part1);
+// gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) _rx_buffer_part1;
+//
+// _gps_position->satellites_visible = packet->numVis;
+// _gps_position->counter++;
+// _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time();
+//
+// break;
+// }
+ case ACK_ACK: {
+// printf("GOT ACK_ACK\n");
+ gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer;
+
+ if (_waiting_for_ack) {
+ if (packet->clsID == _clsID_needed && packet->msgID == _msgID_needed) {
+ ret = 1;
+ }
+ }
+ }
+ break;
+
+ case ACK_NAK: {
+// printf("GOT ACK_NAK\n");
+ warnx("UBX: Received: Not Acknowledged");
+ /* configuration obviously not successful */
+ ret = -1;
+ break;
+ }
+
+ default: //we don't know the message
+ warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id);
+ ret = -1;
+ break;
+ }
+ // end if _rx_count high enough
+ decode_init();
+ return ret; //XXX?
+}
+
+void
+UBX::decode_init(void)
+{
+ _rx_ck_a = 0;
+ _rx_ck_b = 0;
+ _rx_count = 0;
+ _decode_state = UBX_DECODE_UNINIT;
+ _message_class = CLASS_UNKNOWN;
+ _message_id = ID_UNKNOWN;
+ _payload_size = 0;
+}
+
+void
+UBX::add_byte_to_checksum(uint8_t b)
+{
+ _rx_ck_a = _rx_ck_a + b;
+ _rx_ck_b = _rx_ck_b + _rx_ck_a;
+}
+
+void
+UBX::add_checksum_to_message(uint8_t* message, const unsigned length)
+{
+ uint8_t ck_a = 0;
+ uint8_t ck_b = 0;
+ unsigned i;
+
+ for (i = 0; i < length-2; i++) {
+ ck_a = ck_a + message[i];
+ ck_b = ck_b + ck_a;
+ }
+ /* The checksum is written to the last to bytes of a message */
+ message[length-2] = ck_a;
+ message[length-1] = ck_b;
+}
+
+void
+UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length)
+{
+ ssize_t ret = 0;
+
+ /* Calculate the checksum now */
+ add_checksum_to_message(packet, length);
+
+ const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2};
+
+ /* Start with the two sync bytes */
+ ret += write(fd, sync_bytes, sizeof(sync_bytes));
+ ret += write(fd, packet, length);
+
+ if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning?
+ warnx("ubx: config write fail");
+}
diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h
new file mode 100644
index 000000000..e3dd1c7ea
--- /dev/null
+++ b/apps/drivers/gps/ubx.h
@@ -0,0 +1,395 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 PX4 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.
+ *
+ ****************************************************************************/
+
+/* @file U-Blox protocol definitions */
+
+#ifndef UBX_H_
+#define UBX_H_
+
+#include "gps_helper.h"
+
+#define UBX_SYNC1 0xB5
+#define UBX_SYNC2 0x62
+
+/* ClassIDs (the ones that are used) */
+#define UBX_CLASS_NAV 0x01
+//#define UBX_CLASS_RXM 0x02
+#define UBX_CLASS_ACK 0x05
+#define UBX_CLASS_CFG 0x06
+
+/* MessageIDs (the ones that are used) */
+#define UBX_MESSAGE_NAV_POSLLH 0x02
+#define UBX_MESSAGE_NAV_SOL 0x06
+#define UBX_MESSAGE_NAV_TIMEUTC 0x21
+//#define UBX_MESSAGE_NAV_DOP 0x04
+#define UBX_MESSAGE_NAV_SVINFO 0x30
+#define UBX_MESSAGE_NAV_VELNED 0x12
+//#define UBX_MESSAGE_RXM_SVSI 0x20
+#define UBX_MESSAGE_ACK_ACK 0x01
+#define UBX_MESSAGE_ACK_NAK 0x00
+#define UBX_MESSAGE_CFG_PRT 0x00
+#define UBX_MESSAGE_CFG_NAV5 0x24
+#define UBX_MESSAGE_CFG_MSG 0x01
+#define UBX_MESSAGE_CFG_RATE 0x08
+
+#define UBX_CFG_PRT_LENGTH 20
+#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
+#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
+#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */
+#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */
+#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */
+
+#define UBX_CFG_RATE_LENGTH 6
+#define UBX_CFG_RATE_PAYLOAD_MEASRATE 200 /**< 200ms for 5Hz */
+#define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */
+#define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */
+
+
+#define UBX_CFG_NAV5_LENGTH 36
+#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0001 /**< only update dynamic model and fix mode */
+#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */
+#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */
+
+#define UBX_CFG_MSG_LENGTH 8
+#define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
+#define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
+
+#define UBX_MAX_PAYLOAD_LENGTH 500
+
+// ************
+/** the structures of the binary packets */
+#pragma pack(push, 1)
+
+typedef struct {
+ uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
+ int32_t lon; /**< Longitude * 1e-7, deg */
+ int32_t lat; /**< Latitude * 1e-7, deg */
+ int32_t height; /**< Height above Ellipsoid, mm */
+ int32_t height_msl; /**< Height above mean sea level, mm */
+ uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */
+ uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_nav_posllh_packet_t;
+
+typedef struct {
+ uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
+ int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */
+ int16_t week; /**< GPS week (GPS time) */
+ uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
+ uint8_t flags;
+ int32_t ecefX;
+ int32_t ecefY;
+ int32_t ecefZ;
+ uint32_t pAcc;
+ int32_t ecefVX;
+ int32_t ecefVY;
+ int32_t ecefVZ;
+ uint32_t sAcc;
+ uint16_t pDOP;
+ uint8_t reserved1;
+ uint8_t numSV;
+ uint32_t reserved2;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_nav_sol_packet_t;
+
+typedef struct {
+ uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
+ uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */
+ int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */
+ uint16_t year; /**< Year, range 1999..2099 (UTC) */
+ uint8_t month; /**< Month, range 1..12 (UTC) */
+ uint8_t day; /**< Day of Month, range 1..31 (UTC) */
+ uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */
+ uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */
+ uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */
+ uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_nav_timeutc_packet_t;
+
+//typedef struct {
+// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
+// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */
+// uint16_t pDOP; /**< Position DOP (scaling 0.01) */
+// uint16_t tDOP; /**< Time DOP (scaling 0.01) */
+// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */
+// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */
+// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */
+// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */
+// uint8_t ck_a;
+// uint8_t ck_b;
+//} gps_bin_nav_dop_packet_t;
+
+typedef struct {
+ uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
+ uint8_t numCh; /**< Number of channels */
+ uint8_t globalFlags;
+ uint16_t reserved2;
+
+} gps_bin_nav_svinfo_part1_packet_t;
+
+typedef struct {
+ uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
+ uint8_t svid; /**< Satellite ID */
+ uint8_t flags;
+ uint8_t quality;
+ uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */
+ int8_t elev; /**< Elevation in integer degrees */
+ int16_t azim; /**< Azimuth in integer degrees */
+ int32_t prRes; /**< Pseudo range residual in centimetres */
+
+} gps_bin_nav_svinfo_part2_packet_t;
+
+typedef struct {
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_nav_svinfo_part3_packet_t;
+
+typedef struct {
+ uint32_t time_milliseconds; // GPS Millisecond Time of Week
+ int32_t velN; //NED north velocity, cm/s
+ int32_t velE; //NED east velocity, cm/s
+ int32_t velD; //NED down velocity, cm/s
+ uint32_t speed; //Speed (3-D), cm/s
+ uint32_t gSpeed; //Ground Speed (2-D), cm/s
+ int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5
+ uint32_t sAcc; //Speed Accuracy Estimate, cm/s
+ uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_nav_velned_packet_t;
+
+//typedef struct {
+// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
+// int16_t week; /**< Measurement GPS week number */
+// uint8_t numVis; /**< Number of visible satellites */
+//
+// //... rest of package is not used in this implementation
+//
+//} gps_bin_rxm_svsi_packet_t;
+
+typedef struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_ack_ack_packet_t;
+
+typedef struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} gps_bin_ack_nak_packet_t;
+
+typedef struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ uint16_t length;
+ uint8_t portID;
+ uint8_t res0;
+ uint16_t res1;
+ uint32_t mode;
+ uint32_t baudRate;
+ uint16_t inProtoMask;
+ uint16_t outProtoMask;
+ uint16_t flags;
+ uint16_t pad;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} type_gps_bin_cfg_prt_packet_t;
+
+typedef struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ uint16_t length;
+ uint16_t measRate;
+ uint16_t navRate;
+ uint16_t timeRef;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} type_gps_bin_cfg_rate_packet_t;
+
+typedef struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ uint16_t length;
+ uint16_t mask;
+ uint8_t dynModel;
+ uint8_t fixMode;
+ int32_t fixedAlt;
+ uint32_t fixedAltVar;
+ int8_t minElev;
+ uint8_t drLimit;
+ uint16_t pDop;
+ uint16_t tDop;
+ uint16_t pAcc;
+ uint16_t tAcc;
+ uint8_t staticHoldThresh;
+ uint8_t dgpsTimeOut;
+ uint32_t reserved2;
+ uint32_t reserved3;
+ uint32_t reserved4;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} type_gps_bin_cfg_nav5_packet_t;
+
+typedef struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ uint16_t length;
+ uint8_t msgClass_payload;
+ uint8_t msgID_payload;
+ uint8_t rate[6];
+ uint8_t ck_a;
+ uint8_t ck_b;
+} type_gps_bin_cfg_msg_packet_t;
+
+
+// END the structures of the binary packets
+// ************
+
+typedef enum {
+ UBX_CONFIG_STATE_PRT = 0,
+ UBX_CONFIG_STATE_PRT_NEW_BAUDRATE,
+ UBX_CONFIG_STATE_RATE,
+ UBX_CONFIG_STATE_NAV5,
+ UBX_CONFIG_STATE_MSG_NAV_POSLLH,
+ UBX_CONFIG_STATE_MSG_NAV_TIMEUTC,
+ UBX_CONFIG_STATE_MSG_NAV_DOP,
+ UBX_CONFIG_STATE_MSG_NAV_SVINFO,
+ UBX_CONFIG_STATE_MSG_NAV_SOL,
+ UBX_CONFIG_STATE_MSG_NAV_VELNED,
+// UBX_CONFIG_STATE_MSG_RXM_SVSI,
+ UBX_CONFIG_STATE_CONFIGURED
+} ubx_config_state_t;
+
+typedef enum {
+ CLASS_UNKNOWN = 0,
+ NAV = 1,
+ RXM = 2,
+ ACK = 3,
+ CFG = 4
+} ubx_message_class_t;
+
+typedef enum {
+ //these numbers do NOT correspond to the message id numbers of the ubx protocol
+ ID_UNKNOWN = 0,
+ NAV_POSLLH,
+ NAV_SOL,
+ NAV_TIMEUTC,
+// NAV_DOP,
+ NAV_SVINFO,
+ NAV_VELNED,
+// RXM_SVSI,
+ CFG_NAV5,
+ ACK_ACK,
+ ACK_NAK,
+} ubx_message_id_t;
+
+typedef enum {
+ UBX_DECODE_UNINIT = 0,
+ UBX_DECODE_GOT_SYNC1,
+ UBX_DECODE_GOT_SYNC2,
+ UBX_DECODE_GOT_CLASS,
+ UBX_DECODE_GOT_MESSAGEID,
+ UBX_DECODE_GOT_LENGTH1,
+ UBX_DECODE_GOT_LENGTH2
+} ubx_decode_state_t;
+
+//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
+#pragma pack(pop)
+
+#define RECV_BUFFER_SIZE 500 //The NAV-SOL messages really need such a big buffer
+
+class UBX : public GPS_Helper
+{
+public:
+ UBX(const int &fd, struct vehicle_gps_position_s *gps_position);
+ ~UBX();
+ int receive(unsigned timeout);
+ int configure(unsigned &baudrate);
+
+private:
+
+ /**
+ * Parse the binary MTK packet
+ */
+ int parse_char(uint8_t b);
+
+ /**
+ * Handle the package once it has arrived
+ */
+ int handle_message(void);
+
+ /**
+ * Reset the parse state machine for a fresh start
+ */
+ void decode_init(void);
+
+ /**
+ * While parsing add every byte (except the sync bytes) to the checksum
+ */
+ void add_byte_to_checksum(uint8_t);
+
+ /**
+ * Add the two checksum bytes to an outgoing message
+ */
+ void add_checksum_to_message(uint8_t* message, const unsigned length);
+
+ /**
+ * Helper to send a config packet
+ */
+ void send_config_packet(const int &fd, uint8_t *packet, const unsigned length);
+
+ int _fd;
+ struct vehicle_gps_position_s *_gps_position;
+ ubx_config_state_t _config_state;
+ bool _waiting_for_ack;
+ uint8_t _clsID_needed;
+ uint8_t _msgID_needed;
+ ubx_decode_state_t _decode_state;
+ uint8_t _rx_buffer[RECV_BUFFER_SIZE];
+ unsigned _rx_count;
+ uint8_t _rx_ck_a;
+ uint8_t _rx_ck_b;
+ ubx_message_class_t _message_class;
+ ubx_message_id_t _message_id;
+ unsigned _payload_size;
+};
+
+#endif /* UBX_H_ */
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
diff --git a/apps/gps/.context b/apps/gps/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/apps/gps/.context
+++ /dev/null
diff --git a/apps/gps/.gitignore b/apps/gps/.gitignore
deleted file mode 100644
index a02827195..000000000
--- a/apps/gps/.gitignore
+++ /dev/null
@@ -1,3 +0,0 @@
-include
-mavlink-*
-pymavlink-*
diff --git a/apps/gps/gps.c b/apps/gps/gps.c
deleted file mode 100644
index 8a9512054..000000000
--- a/apps/gps/gps.c
+++ /dev/null
@@ -1,589 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- *
- * 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 PX4 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.
- *
- ****************************************************************************/
-
-/* @file gps.c
- * GPS app main loop.
- */
-
-#include "gps.h"
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdlib.h>
-#include <stdio.h>
-#include <stdbool.h>
-#include <fcntl.h>
-#include "nmealib/nmea/nmea.h" // the nmea library
-#include "nmea_helper.h" //header files for interacting with the nmea library
-#include "mtk.h" //header files for the custom protocol for the mediatek diydrones chip
-#include "ubx.h" //header files for the ubx protocol
-#include <termios.h>
-#include <signal.h>
-#include <pthread.h>
-#include <sys/prctl.h>
-#include <errno.h>
-#include <signal.h>
-#include <v1.0/common/mavlink.h>
-#include <mavlink/mavlink_log.h>
-
-#include <systemlib/systemlib.h>
-
-static bool thread_should_exit; /**< Deamon status flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-
-/**
- * GPS module readout and publishing.
- *
- * This function reads the onboard gps and publishes the vehicle_gps_positon topic.
- *
- * @see vehicle_gps_position_s
- * @ingroup apps
- */
-__EXPORT int gps_main(int argc, char *argv[]);
-
-/**
- * Mainloop of deamon.
- */
-int gps_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-#define IMPORTANT_GPS_BAUD_RATES_N 2
-#define RETRY_INTERVAL_SECONDS 10
-
-//gps_bin_ubx_state_t * ubx_state;
-bool gps_mode_try_all;
-bool gps_baud_try_all;
-bool gps_mode_success;
-bool terminate_gps_thread;
-bool gps_verbose;
-int current_gps_speed;
-
-enum GPS_MODES {
- GPS_MODE_START = 0,
- GPS_MODE_UBX = 1,
- GPS_MODE_MTK = 2,
- GPS_MODE_NMEA = 3,
- GPS_MODE_END = 4
-};
-
-
-#define AUTO_DETECTION_COUNT 8
-const int autodetection_baudrates[] = {B38400, B9600, B38400, B9600, B38400, B9600, B38400, B9600};
-const enum GPS_MODES autodetection_gpsmodes[] = {GPS_MODE_UBX, GPS_MODE_UBX, GPS_MODE_MTK, GPS_MODE_MTK, GPS_MODE_UBX, GPS_MODE_UBX, GPS_MODE_NMEA, GPS_MODE_NMEA}; //nmea is the fall-back if nothing else works, therefore we try the standard modes again before finally trying nmea
-
-/****************************************************************************
- * Private functions
- ****************************************************************************/
-int open_port(char *port);
-
-void close_port(int *fd);
-
-void setup_port(char *device, int speed, int *fd);
-
-
-/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int gps_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("gps already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn("gps",
- SCHED_DEFAULT,
- SCHED_PRIORITY_DEFAULT,
- 4096,
- gps_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- thread_running = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- printf("\tgps is running\n");
- } else {
- printf("\tgps not started\n");
- }
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-/*
- * Main function of gps app.
- */
-int gps_thread_main(int argc, char *argv[]) {
-
- /* welcome message */
- printf("[gps] Initialized. Searching for GPS receiver..\n");
-
- /* default values */
- const char *commandline_usage = "\tusage: %s {start|stop|status} -d devicename -b baudrate -m mode\n\tmodes are:\n\t\tubx\n\t\tmtkcustom\n\t\tnmea\n\t\tall\n";
- char *device = "/dev/ttyS3";
- char mode[10];
- strcpy(mode, "all");
- int baudrate = -1;
- gps_mode_try_all = false;
- gps_baud_try_all = false;
- gps_mode_success = true;
- terminate_gps_thread = false;
- bool retry = false;
- gps_verbose = false;
-
- int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
- /* read arguments */
- int i;
-
- for (i = 0; i < argc; i++) {
- if (strcmp(argv[i], "-h") == 0 || strcmp(argv[i], "--help") == 0) { //device set
- printf(commandline_usage, argv[0]);
- thread_running = false;
- return 0;
- }
-
- if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set
- if (argc > i + 1) {
- device = argv[i + 1];
-
- } else {
- printf(commandline_usage, argv[0]);
- thread_running = false;
- return 0;
- }
- }
-
- if (strcmp(argv[i], "-r") == 0 || strcmp(argv[i], "--retry") == 0) {
- if (argc > i + 1) {
- retry = atoi(argv[i + 1]);
-
- } else {
- printf(commandline_usage, argv[0]);
- thread_running = false;
- return 0;
- }
- }
-
- if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--baud") == 0) {
- if (argc > i + 1) {
- baudrate = atoi(argv[i + 1]);
-
- } else {
- printf(commandline_usage, argv[0]);
- thread_running = false;
- return 0;
- }
- }
-
- if (strcmp(argv[i], "-m") == 0 || strcmp(argv[i], "--mode") == 0) {
- if (argc > i + 1) {
- strcpy(mode, argv[i + 1]);
-
- } else {
- printf(commandline_usage, argv[0]);
- thread_running = false;
- return 0;
- }
- }
-
- if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) {
- gps_verbose = true;
- }
- }
-
- /*
- * In case a baud rate is set only this baud rate will be tried,
- * otherwise a array of usual baud rates for gps receivers is used
- */
-
-
-// printf("baudrate = %d\n",baudrate);
- switch (baudrate) {
- case -1: gps_baud_try_all = true; break;
-
- case 0: current_gps_speed = B0; break;
- case 50: current_gps_speed = B50; break;
- case 75: current_gps_speed = B75; break;
- case 110: current_gps_speed = B110; break;
- case 134: current_gps_speed = B134; break;
- case 150: current_gps_speed = B150; break;
- case 200: current_gps_speed = B200; break;
- case 300: current_gps_speed = B300; break;
- case 600: current_gps_speed = B600; break;
- case 1200: current_gps_speed = B1200; break;
- case 1800: current_gps_speed = B1800; break;
- case 2400: current_gps_speed = B2400; break;
- case 4800: current_gps_speed = B4800; break;
- case 9600: current_gps_speed = B9600; break;
- case 19200: current_gps_speed = B19200; break;
- case 38400: current_gps_speed = B38400; break;
- case 57600: current_gps_speed = B57600; break;
- case 115200: current_gps_speed = B115200; break;
- case 230400: current_gps_speed = B230400; break;
- case 460800: current_gps_speed = B460800; break;
- case 921600: current_gps_speed = B921600; break;
-
- default:
- fprintf(stderr, "[gps] ERROR: Unsupported baudrate: %d\n", baudrate);
- fflush(stdout);
- return -EINVAL;
- }
-
-
- enum GPS_MODES current_gps_mode = GPS_MODE_UBX;
-
- if (strcmp(mode, "ubx") == 0) {
- current_gps_mode = GPS_MODE_UBX;
-
- } else if (strcmp(mode, "mtkcustom") == 0) {
- current_gps_mode = GPS_MODE_MTK;
-
- } else if (strcmp(mode, "nmea") == 0) {
- current_gps_mode = GPS_MODE_NMEA;
-
- } else if (strcmp(mode, "all") == 0) {
- gps_mode_try_all = true;
-
- } else {
- fprintf(stderr, "\t[gps] Invalid mode argument\n");
- printf(commandline_usage);
- thread_running = false;
- return ERROR;
- }
-
- /* Declare file descriptor for gps here, open port later in setup_port */
- int fd;
-
- while (!thread_should_exit) {
- /* Infinite retries or break if retry == false */
-
- /* Loop over all configurations of baud rate and protocol */
- for (i = 0; i < AUTO_DETECTION_COUNT; i++) {
- if (gps_mode_try_all) {
- current_gps_mode = autodetection_gpsmodes[i];
-
- if (false == gps_baud_try_all && autodetection_baudrates[i] != current_gps_speed) //there is no need to try modes which are not configured to run with the selcted baud rate
- continue;
- }
-
- if (gps_baud_try_all) {
- current_gps_speed = autodetection_baudrates[i];
-
- if (false == gps_mode_try_all && autodetection_gpsmodes[i] != current_gps_mode) //there is no need to try baud rates which are not usual for the selected mode
- continue;
- }
-
-
- /*
- * The watchdog_thread will return and set gps_mode_success to false if no data can be parsed.
- * if the gps was once running the wtachdog thread will not return but instead try to reconfigure the gps (depending on the mode/protocol)
- */
-
- if (current_gps_mode == GPS_MODE_UBX) {
-
- if (gps_verbose) printf("[gps] Trying UBX mode at %d baud\n", current_gps_speed);
-
- mavlink_log_info(mavlink_fd, "[gps] trying to connect to a ubx module");
-
- setup_port(device, current_gps_speed, &fd);
-
- /* start ubx thread and watchdog */
- pthread_t ubx_thread;
- pthread_t ubx_watchdog_thread;
-
- pthread_mutex_t ubx_mutex_d;
- ubx_mutex = &ubx_mutex_d;
- pthread_mutex_init(ubx_mutex, NULL);
- gps_bin_ubx_state_t ubx_state_d;
- ubx_state = &ubx_state_d;
- ubx_decode_init();
-
- pthread_attr_t ubx_loop_attr;
- pthread_attr_init(&ubx_loop_attr);
- pthread_attr_setstacksize(&ubx_loop_attr, 3000);
-
- struct arg_struct args;
- args.fd_ptr = &fd;
- args.thread_should_exit_ptr = &thread_should_exit;
-
- pthread_create(&ubx_thread, &ubx_loop_attr, ubx_loop, (void *)&args);
-
- pthread_attr_t ubx_wd_attr;
- pthread_attr_init(&ubx_wd_attr);
- pthread_attr_setstacksize(&ubx_wd_attr, 1400);
- int pthread_create_res = pthread_create(&ubx_watchdog_thread, &ubx_wd_attr, ubx_watchdog_loop, (void *)&args);
-
- if (pthread_create_res != 0) fprintf(stderr, "[gps] ERROR: could not create ubx watchdog thread, pthread_create =%d\n", pthread_create_res);
-
- /* wait for threads to complete */
- pthread_join(ubx_watchdog_thread, NULL);
-
- if (gps_mode_success == false) {
- if (gps_verbose) printf("[gps] no success with UBX mode and %d baud\n", current_gps_speed);
-
- terminate_gps_thread = true;
- pthread_join(ubx_thread, NULL);
-
- gps_mode_success = true;
- terminate_gps_thread = false;
-
- /* maybe the watchdog was stopped through the thread_should_exit flag */
- } else if (thread_should_exit) {
- pthread_join(ubx_thread, NULL);
- if (gps_verbose) printf("[gps] ubx watchdog and ubx loop threads have been terminated, exiting.");
- close(mavlink_fd);
- close_port(&fd);
- thread_running = false;
- return 0;
- }
-
- close_port(&fd);
- } else if (current_gps_mode == GPS_MODE_MTK) {
- if (gps_verbose) printf("[gps] trying MTK binary mode at %d baud\n", current_gps_speed);
-
- mavlink_log_info(mavlink_fd, "[gps] trying to connect to a MTK module");
-
- setup_port(device, current_gps_speed, &fd);
-
- /* start mtk thread and watchdog */
- pthread_t mtk_thread;
- pthread_t mtk_watchdog_thread;
-
- pthread_mutex_t mtk_mutex_d;
- mtk_mutex = &mtk_mutex_d;
- pthread_mutex_init(mtk_mutex, NULL);
-
-
- gps_bin_mtk_state_t mtk_state_d;
- mtk_state = &mtk_state_d;
- mtk_decode_init();
-
-
- pthread_attr_t mtk_loop_attr;
- pthread_attr_init(&mtk_loop_attr);
- pthread_attr_setstacksize(&mtk_loop_attr, 2048);
-
- struct arg_struct args;
- args.fd_ptr = &fd;
- args.thread_should_exit_ptr = &thread_should_exit;
-
- pthread_create(&mtk_thread, &mtk_loop_attr, mtk_loop, (void *)&args);
- sleep(2);
- pthread_create(&mtk_watchdog_thread, NULL, mtk_watchdog_loop, (void *)&args);
-
- /* wait for threads to complete */
- pthread_join(mtk_watchdog_thread, (void *)&fd);
-
- if (gps_mode_success == false) {
- if (gps_verbose) printf("[gps] No success with MTK binary mode and %d baud\n", current_gps_speed);
-
- terminate_gps_thread = true;
- pthread_join(mtk_thread, NULL);
-
- //if(true == gps_mode_try_all)
- //strcpy(mode, "nmea");
-
- gps_mode_success = true;
- terminate_gps_thread = false;
- }
-
- close_port(&fd);
-
- } else if (current_gps_mode == GPS_MODE_NMEA) {
- if (gps_verbose) printf("[gps] Trying NMEA mode at %d baud\n", current_gps_speed);
-
- mavlink_log_info(mavlink_fd, "[gps] trying to connect to a NMEA module");
-
-
- setup_port(device, current_gps_speed, &fd);
-
- /* start nmea thread and watchdog */
- pthread_t nmea_thread;
- pthread_t nmea_watchdog_thread;
-
- pthread_mutex_t nmea_mutex_d;
- nmea_mutex = &nmea_mutex_d;
- pthread_mutex_init(nmea_mutex, NULL);
-
- gps_bin_nmea_state_t nmea_state_d;
- nmea_state = &nmea_state_d;
-
- pthread_attr_t nmea_loop_attr;
- pthread_attr_init(&nmea_loop_attr);
- pthread_attr_setstacksize(&nmea_loop_attr, 4096);
-
- struct arg_struct args;
- args.fd_ptr = &fd;
- args.thread_should_exit_ptr = &thread_should_exit;
-
- pthread_create(&nmea_thread, &nmea_loop_attr, nmea_loop, (void *)&args);
- sleep(2);
- pthread_create(&nmea_watchdog_thread, NULL, nmea_watchdog_loop, (void *)&args);
-
- /* wait for threads to complete */
- pthread_join(nmea_watchdog_thread, (void *)&fd);
-
- if (gps_mode_success == false) {
- if (gps_verbose) printf("[gps] No success with NMEA mode and %d baud\r\n", current_gps_speed);
-
- terminate_gps_thread = true;
- pthread_join(nmea_thread, NULL);
-
- gps_mode_success = true;
- terminate_gps_thread = false;
- }
-
- close_port(&fd);
- }
-
- /* exit quickly if stop command has been received */
- if (thread_should_exit) {
- printf("[gps] stopped, exiting.\n");
- close(mavlink_fd);
- thread_running = false;
- return 0;
- }
-
- /* if both, mode and baud is set by argument, we only need one loop*/
- if (gps_mode_try_all == false && gps_baud_try_all == false)
- break;
- }
-
-
- if (retry) {
- printf("[gps] No configuration was successful, retrying in %d seconds \n", RETRY_INTERVAL_SECONDS);
- mavlink_log_info(mavlink_fd, "[gps] No configuration was successful, retrying...");
- fflush(stdout);
-
- } else {
- fprintf(stderr, "[gps] No configuration was successful, exiting... \n");
- fflush(stdout);
- mavlink_log_info(mavlink_fd, "[gps] No configuration was successful, exiting...");
- break;
- }
-
- sleep(RETRY_INTERVAL_SECONDS);
- }
-
- printf("[gps] exiting.\n");
- close(mavlink_fd);
- thread_running = false;
- return 0;
-}
-
-
-static void usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "\tusage: gps {start|status|stop} -d devicename -b baudrate -m mode\n\tmodes are:\n\t\tubx\n\t\tmtkcustom\n\t\tnmea\n\t\tall\n");
- exit(1);
-}
-
-int open_port(char *port)
-{
- int fd; /**< File descriptor for the gps port */
-
- /* Open serial port */
- fd = open(port, O_CREAT | O_RDWR | O_NOCTTY); /* O_RDWR - Read and write O_NOCTTY - Ignore special chars like CTRL-C */
- return (fd);
-}
-
-
-void close_port(int *fd)
-{
- /* Close serial port */
- close(*fd);
-}
-
-void setup_port(char *device, int speed, int *fd)
-{
- /* open port (baud rate is set in defconfig file) */
- *fd = open_port(device);
-
- if (*fd != -1) {
- if (gps_verbose) printf("[gps] Port opened: %s at %d baud\n", device, speed);
-
- } else {
- fprintf(stderr, "[gps] Could not open port, exiting gps app!\n");
- fflush(stdout);
- }
-
- /* Try to set baud rate */
- struct termios uart_config;
- int termios_state;
-
- if ((termios_state = tcgetattr(*fd, &uart_config)) < 0) {
- fprintf(stderr, "[gps] ERROR getting baudrate / termios config for %s: %d\n", device, termios_state);
- close(*fd);
- }
- if (gps_verbose) printf("[gps] Try to set baud rate %d now\n",speed);
- /* Set baud rate */
- cfsetispeed(&uart_config, speed);
- cfsetospeed(&uart_config, speed);
- if ((termios_state = tcsetattr(*fd, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[gps] ERROR setting baudrate / termios config for %s (tcsetattr)\n", device);
- close(*fd);
- }
-}
diff --git a/apps/gps/gps.h b/apps/gps/gps.h
deleted file mode 100644
index 499a6164f..000000000
--- a/apps/gps/gps.h
+++ /dev/null
@@ -1,18 +0,0 @@
-/*
- * gps.h
- *
- * Created on: Mar 8, 2012
- * Author: thomasgubler
- */
-
-#ifndef GPS_H_
-#define GPS_H
-
-#include <stdbool.h>
-
-struct arg_struct {
- int *fd_ptr;
- bool *thread_should_exit_ptr;
-};
-
-#endif /* GPS_H_ */
diff --git a/apps/gps/mtk.c b/apps/gps/mtk.c
deleted file mode 100644
index 3b0ee4565..000000000
--- a/apps/gps/mtk.c
+++ /dev/null
@@ -1,432 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Julian Oes <joes@student.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- *
- * 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 PX4 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.
- *
- ****************************************************************************/
-
-/* @file MTK custom binary (3DR) protocol implementation */
-
-#include "gps.h"
-#include "mtk.h"
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <sys/prctl.h>
-#include <pthread.h>
-#include <poll.h>
-#include <fcntl.h>
-#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <mavlink/mavlink_log.h>
-
-#define MTK_HEALTH_SUCCESS_COUNTER_LIMIT 2
-#define MTK_HEALTH_FAIL_COUNTER_LIMIT 2
-
-// XXX decrease this substantially, it should be only a few dozen bytes max.
-#warning XXX trying 128 for now
-#define MTK_BUFFER_SIZE 128
-
-pthread_mutex_t *mtk_mutex;
-gps_bin_mtk_state_t *mtk_state;
-static struct vehicle_gps_position_s *mtk_gps;
-
-extern bool gps_mode_try_all;
-extern bool gps_mode_success;
-extern bool terminate_gps_thread;
-extern bool gps_baud_try_all;
-extern bool gps_verbose;
-extern int current_gps_speed;
-
-
-void mtk_decode_init(void)
-{
- mtk_state->ck_a = 0;
- mtk_state->ck_b = 0;
- mtk_state->rx_count = 0;
- mtk_state->decode_state = MTK_DECODE_UNINIT;
- mtk_state->print_errors = false;
-}
-
-void mtk_checksum(uint8_t b, uint8_t *ck_a, uint8_t *ck_b)
-{
- *(ck_a) = *(ck_a) + b;
- *(ck_b) = *(ck_b) + *(ck_a);
-// printf("Checksum now: %d\n",*(ck_b));
-}
-
-
-
-int mtk_parse(uint8_t b, char *gps_rx_buffer)
-{
-// printf("b=%x\n",b);
- // Debug output to telemetry port
- // PIOS_COM_SendBufferNonBlocking(PIOS_COM_TELEM_RF, &b, 1);
- if (mtk_state->decode_state == MTK_DECODE_UNINIT) {
-
- if (b == 0xd0) {
- mtk_state->decode_state = MTK_DECODE_GOT_CK_A;
- }
-
- } else if (mtk_state->decode_state == MTK_DECODE_GOT_CK_A) {
- if (b == 0xdd) {
- mtk_state->decode_state = MTK_DECODE_GOT_CK_B;
-
- } else {
- // Second start symbol was wrong, reset state machine
- mtk_decode_init();
- }
-
- } else if (mtk_state->decode_state == MTK_DECODE_GOT_CK_B) {
- // Add to checksum
- if (mtk_state->rx_count < 33) mtk_checksum(b, &(mtk_state->ck_a), &(mtk_state->ck_b));
-
- // Fill packet buffer
- gps_rx_buffer[mtk_state->rx_count] = b;
- (mtk_state->rx_count)++;
-// printf("Rx count: %d\n",mtk_state->rx_count);
- uint8_t ret = 0;
-
- /* Packet size minus checksum */
- if (mtk_state->rx_count >= 35) {
- gps_bin_mtk_packet_t *packet = (gps_bin_mtk_packet_t *) gps_rx_buffer;
-
- /* Check if checksum is valid */
- if (mtk_state->ck_a == packet->ck_a && mtk_state->ck_b == packet->ck_b) {
- mtk_gps->lat = packet->latitude * 10; // mtk: degrees*1e6, mavlink/ubx: degrees*1e7
- mtk_gps->lon = packet->longitude * 10; // mtk: degrees*1e6, mavlink/ubx: degrees*1e7
- mtk_gps->alt = (int32_t)(packet->msl_altitude * 10); // conversion from centimeters to millimeters, and from uint32_t to int16_t
- mtk_gps->fix_type = packet->fix_type;
- mtk_gps->eph = packet->hdop;
- mtk_gps->epv = 65535; //unknown in mtk custom mode
- mtk_gps->vel = packet->ground_speed;
- mtk_gps->cog = (uint16_t)packet->heading; //mtk: degrees *1e2, mavlink/ubx: degrees *1e2
- mtk_gps->satellites_visible = packet->satellites;
-
- /* convert time and date information to unix timestamp */
- struct tm timeinfo; //TODO: test this conversion
- uint32_t timeinfo_conversion_temp;
-
- timeinfo.tm_mday = packet->date * 1e-4;
- timeinfo_conversion_temp = packet->date - timeinfo.tm_mday * 1e4;
- timeinfo.tm_mon = timeinfo_conversion_temp * 1e-2 - 1;
- timeinfo.tm_year = (timeinfo_conversion_temp - (timeinfo.tm_mon + 1) * 1e2) + 100;
-
- timeinfo.tm_hour = packet->utc_time * 1e-7;
- timeinfo_conversion_temp = packet->utc_time - timeinfo.tm_hour * 1e7;
- timeinfo.tm_min = timeinfo_conversion_temp * 1e-5;
- timeinfo_conversion_temp -= timeinfo.tm_min * 1e5;
- timeinfo.tm_sec = timeinfo_conversion_temp * 1e-3;
- timeinfo_conversion_temp -= timeinfo.tm_sec * 1e3;
- time_t epoch = mktime(&timeinfo);
- mtk_gps->timestamp = hrt_absolute_time();
- mtk_gps->time_gps_usec = epoch * 1e6; //TODO: test this
- mtk_gps->time_gps_usec += timeinfo_conversion_temp * 1e3;
-
- mtk_gps->counter_pos_valid++;
-
- mtk_gps->timestamp = hrt_absolute_time();
-
-// printf("%lu; %lu; %d.%d.%d %d:%d:%d:%d\n", packet->date, packet->utc_time,timeinfo.tm_year, timeinfo.tm_mon, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec, timeinfo_conversion_temp);
-
- pthread_mutex_lock(mtk_mutex);
-// printf("Write timestamp /n");
- mtk_state->last_message_timestamp = hrt_absolute_time();
- pthread_mutex_unlock(mtk_mutex);
-
- ret = 1;
-// printf("found package\n");
-
- } else {
- if (gps_verbose) printf("[gps] Checksum invalid\r\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- mtk_decode_init();
-// printf("prepared for next state\n");
- return ret;
- }
- }
-
- return 0; // no valid packet found
-
-}
-
-int read_gps_mtk(int *fd, char *gps_rx_buffer, int buffer_size) // returns 1 if the thread should terminate
-{
-// printf("in read_gps_mtk\n");
- uint8_t ret = 0;
-
- uint8_t c;
-
- int rx_count = 0;
- int gpsRxOverflow = 0;
-
- struct pollfd fds;
- fds.fd = *fd;
- fds.events = POLLIN;
-
- // This blocks the task until there is something on the buffer
- while (1) {
- //check if the thread should terminate
- if (terminate_gps_thread == true) {
-// printf("terminate_gps_thread=%u ", terminate_gps_thread);
-// printf("exiting mtk thread\n");
-// fflush(stdout);
- ret = 1;
- break;
- }
-
- if (poll(&fds, 1, 1000) > 0) {
- if (read(*fd, &c, 1) > 0) {
-// printf("Read %x\n",c);
- if (rx_count >= buffer_size) {
- // The buffer is already full and we haven't found a valid NMEA sentence.
- // Flush the buffer and note the overflow event.
- gpsRxOverflow++;
- rx_count = 0;
- mtk_decode_init();
-
- if (gps_verbose) printf("[gps] Buffer full\r\n");
-
- } else {
- //gps_rx_buffer[rx_count] = c;
- rx_count++;
-
- }
-
- int msg_read = mtk_parse(c, gps_rx_buffer);
-
- if (msg_read > 0) {
- // printf("Found sequence\n");
- break;
- }
-
- } else {
- break;
- }
-
- } else {
- break;
- }
-
- }
-
- return ret;
-}
-
-int configure_gps_mtk(int *fd)
-{
- int success = 0;
- size_t result_write;
- result_write = write(*fd, MEDIATEK_REFRESH_RATE_10HZ, strlen(MEDIATEK_REFRESH_RATE_10HZ));
-
- if (result_write != strlen(MEDIATEK_REFRESH_RATE_10HZ)) {
- printf("[gps] Set update speed to 10 Hz failed\r\n");
- success = 1;
-
- } else {
- if (gps_verbose) printf("[gps] Attempted to set update speed to 10 Hz..\r\n");
- }
-
- //set custom mode
- result_write = write(*fd, MEDIATEK_CUSTOM_BINARY_MODE, strlen(MEDIATEK_CUSTOM_BINARY_MODE));
-
- if (result_write != strlen(MEDIATEK_CUSTOM_BINARY_MODE)) {
- //global_data_send_subsystem_info(&mtk_present);
- printf("[gps] Set MTK custom mode failed\r\n");
- success = 1;
-
- } else {
- //global_data_send_subsystem_info(&mtk_present_enabled);
- if (gps_verbose) printf("[gps] Attempted to set MTK custom mode..\r\n");
- }
-
- return success;
-}
-
-void *mtk_loop(void *args)
-{
-// int oldstate;
-// pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, oldstate);
-//
-// printf("in mtk loop\n");
- /* Set thread name */
- prctl(PR_SET_NAME, "gps mtk read", getpid());
-
- /* Retrieve file descriptor and thread flag */
- struct arg_struct *arguments = (struct arg_struct *)args;
- int *fd = arguments->fd_ptr;
- bool *thread_should_exit = arguments->thread_should_exit_ptr;
-
- /* Initialize gps stuff */
-// int buffer_size = 1000;
-// char * gps_rx_buffer = malloc(buffer_size*sizeof(char));
- char gps_rx_buffer[MTK_BUFFER_SIZE];
-
- /* set parameters for mtk custom */
-
- if (configure_gps_mtk(fd) != 0) {
- printf("[gps] Could not write serial port..\r\n");
-
- /* Write shared variable sys_status */
-
- //global_data_send_subsystem_info(&mtk_present);
-
- } else {
- if (gps_verbose) printf("[gps] Configuration finished, awaiting GPS data..\r\n");
-
-
- /* Write shared variable sys_status */
-
- //global_data_send_subsystem_info(&mtk_present_enabled);
- }
-
- /* advertise GPS topic */
- struct vehicle_gps_position_s mtk_gps_d;
- mtk_gps = &mtk_gps_d;
- orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), mtk_gps);
-
- while (!(*thread_should_exit)) {
- /* Parse a message from the gps receiver */
- if (OK == read_gps_mtk(fd, gps_rx_buffer, MTK_BUFFER_SIZE)) {
-
- /* publish new GPS position */
- orb_publish(ORB_ID(vehicle_gps_position), gps_handle, mtk_gps);
-
- } else {
- /* de-advertise */
- close(gps_handle);
- break;
- }
-
- }
-
- close(gps_handle);
- if(gps_verbose) printf("[gps] mtk loop is going to terminate\n");
- return NULL;
-}
-
-void *mtk_watchdog_loop(void *args)
-{
-// printf("in mtk watchdog loop\n");
- fflush(stdout);
-
- /* Set thread name */
- prctl(PR_SET_NAME, "gps mtk watchdog", getpid());
-
- /* Retrieve file descriptor and thread flag */
- struct arg_struct *arguments = (struct arg_struct *)args;
- int *fd = arguments->fd_ptr;
- bool *thread_should_exit = arguments->thread_should_exit_ptr;
-
- bool mtk_healthy = false;
-
- uint8_t mtk_fail_count = 0;
- uint8_t mtk_success_count = 0;
- bool once_ok = false;
-
- int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
-
- while (!(*thread_should_exit)) {
- fflush(stdout);
-
- /* if we have no update for a long time reconfigure gps */
- pthread_mutex_lock(mtk_mutex);
- uint64_t timestamp_now = hrt_absolute_time();
- bool all_okay = true;
-
- if (timestamp_now - mtk_state->last_message_timestamp > MTK_WATCHDOG_CRITICAL_TIME_MICROSECONDS) {
- all_okay = false;
- }
-
- pthread_mutex_unlock(mtk_mutex);
-
- if (!all_okay) {
-// printf("mtk unhealthy\n");
- mtk_fail_count++;
- /* gps error */
-// if (err_skip_counter == 0)
-// {
-// printf("[gps] GPS module not connected or not responding..\n");
-// err_skip_counter = 20;
-// }
-// err_skip_counter--;
-
-// printf("gps_mode_try_all =%u, mtk_fail_count=%u, mtk_healthy=%u, once_ok=%u\n", gps_mode_try_all, mtk_fail_count, mtk_healthy, once_ok);
-
- /* If we have too many failures and another mode or baud should be tried, exit... */
- if ((gps_mode_try_all == true || gps_baud_try_all == true) && (mtk_fail_count >= MTK_HEALTH_FAIL_COUNTER_LIMIT) && (mtk_healthy == false) && once_ok == false) {
- if (gps_verbose) printf("[gps] Connection attempt failed, no MTK module found\r\n");
-
- gps_mode_success = false;
- break;
- }
-
- if (mtk_healthy && mtk_fail_count >= MTK_HEALTH_FAIL_COUNTER_LIMIT) {
- printf("[gps] ERROR: MTK GPS module stopped responding\r\n");
- // global_data_send_subsystem_info(&mtk_present_enabled);
- mavlink_log_critical(mavlink_fd, "[gps] MTK module stopped responding\n");
- mtk_healthy = false;
- mtk_success_count = 0;
-
- }
-
- /* trying to reconfigure the gps configuration */
- configure_gps_mtk(fd);
- fflush(stdout);
-
- } else {
- /* gps healthy */
- mtk_success_count++;
- mtk_fail_count = 0;
- once_ok = true; // XXX Should this be true on a single success, or on same criteria as mtk_healthy?
-
- if (!mtk_healthy && mtk_success_count >= MTK_HEALTH_SUCCESS_COUNTER_LIMIT) {
- printf("[gps] MTK module found, status ok (baud=%d)\r\n", current_gps_speed);
- /* MTK never has sat info */
- // XXX Check if lock makes sense here
- mtk_gps->satellite_info_available = 0;
- // global_data_send_subsystem_info(&mtk_present_enabled_healthy);
- mavlink_log_info(mavlink_fd, "[gps] MTK custom binary module found, status ok\n");
- mtk_healthy = true;
- }
- }
-
- usleep(MTK_WATCHDOG_WAIT_TIME_MICROSECONDS);
- }
- if(gps_verbose) printf("[gps] mtk watchdog is going to terminate\n");
- close(mavlink_fd);
- return NULL;
-}
diff --git a/apps/gps/mtk.h b/apps/gps/mtk.h
deleted file mode 100644
index 9fc1caec8..000000000
--- a/apps/gps/mtk.h
+++ /dev/null
@@ -1,98 +0,0 @@
-/*
- * mtk.h
- *
- * Created on: Mar 6, 2012
- * Author: thomasgubler
- */
-
-#ifndef MTK_H_
-#define MTK_H_
-
-#include <stdint.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdio.h>
-#include <stdbool.h>
-#include <unistd.h>
-#include <pthread.h>
-
-//Definition for mtk custom mode
-#define MEDIATEK_REFRESH_RATE_4HZ "$PMTK220,250*29\r\n" //refresh rate - 4Hz - 250 milliseconds
-#define MEDIATEK_REFRESH_RATE_5HZ "$PMTK220,200*2C\r\n"
-#define MEDIATEK_REFRESH_RATE_10HZ "$PMTK220,100*2F\r\n" //refresh rate - 10Hz - 100 milliseconds
-#define MEDIATEK_FACTORY_RESET "$PMTK104*37\r\n" //clear current settings
-#define MEDIATEK_CUSTOM_BINARY_MODE "$PGCMD,16,0,0,0,0,0*6A\r\n"
-#define MEDIATEK_FULL_COLD_RESTART "$PMTK104*37\r\n"
-//#define NMEA_GGA_ENABLE "$PMTK314,0,0,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0*27\r\n" //Set GGA messages
-
-//definitions for watchdog
-#define MTK_WATCHDOG_CRITICAL_TIME_MICROSECONDS 2000000
-#define MTK_WATCHDOG_WAIT_TIME_MICROSECONDS 800000
-
-
-
-
-// ************
-// the structure of the binary packet
-
-typedef struct {
- uint8_t payload; ///< Number of payload bytes
- int32_t latitude; ///< Latitude in degrees * 10^7
- int32_t longitude; ///< Longitude in degrees * 10^7
- uint32_t msl_altitude; ///< MSL altitude in meters * 10^2
- uint32_t ground_speed; ///< FIXME SPEC UNCLEAR
- int32_t heading;
- uint8_t satellites;
- uint8_t fix_type;
- uint32_t date;
- uint32_t utc_time;
- uint16_t hdop;
- uint8_t ck_a;
- uint8_t ck_b;
-} __attribute__((__packed__)) type_gps_bin_mtk_packet;
-
-typedef type_gps_bin_mtk_packet gps_bin_mtk_packet_t;
-
-enum MTK_DECODE_STATES {
- MTK_DECODE_UNINIT = 0,
- MTK_DECODE_GOT_CK_A = 1,
- MTK_DECODE_GOT_CK_B = 2
-};
-
-typedef struct {
- union {
- uint16_t ck;
- struct {
- uint8_t ck_a;
- uint8_t ck_b;
- };
- };
- uint8_t decode_state;
-// bool new_data;
-// uint8_t fix;
- bool print_errors;
- int16_t rx_count;
-
- uint64_t last_message_timestamp;
-} __attribute__((__packed__)) type_gps_bin_mtk_state;
-
-typedef type_gps_bin_mtk_state gps_bin_mtk_state_t;
-
-extern pthread_mutex_t *mtk_mutex;
-extern gps_bin_mtk_state_t *mtk_state;
-
-void mtk_decode_init(void);
-
-void mtk_checksum(uint8_t b, uint8_t *ck_a, uint8_t *ck_b);
-
-int mtk_parse(uint8_t b, char *gps_rx_buffer);
-
-int read_gps_mtk(int *fd, char *gps_rx_buffer, int buffer_size);
-
-int configure_gps_mtk(int *fd);
-
-void *mtk_loop(void *args);
-
-void *mtk_watchdog_loop(void *args);
-
-#endif /* MTK_H_ */
diff --git a/apps/gps/nmea_helper.c b/apps/gps/nmea_helper.c
deleted file mode 100644
index 1a50371c1..000000000
--- a/apps/gps/nmea_helper.c
+++ /dev/null
@@ -1,345 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Julian Oes <joes@student.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- *
- * 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 PX4 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.
- *
- ****************************************************************************/
-
-/* @file NMEA protocol implementation */
-#include "gps.h"
-#include "nmea_helper.h"
-#include <sys/prctl.h>
-#include <unistd.h>
-#include <poll.h>
-#include <fcntl.h>
-#include <unistd.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <mavlink/mavlink_log.h>
-#include <drivers/drv_hrt.h>
-
-#define NMEA_HEALTH_SUCCESS_COUNTER_LIMIT 2
-#define NMEA_HEALTH_FAIL_COUNTER_LIMIT 2
-
-#define NMEA_BUFFER_SIZE 1000
-
-pthread_mutex_t *nmea_mutex;
-gps_bin_nmea_state_t *nmea_state;
-static struct vehicle_gps_position_s *nmea_gps;
-
-extern bool gps_mode_try_all;
-extern bool gps_mode_success;
-extern bool terminate_gps_thread;
-extern bool gps_baud_try_all;
-extern bool gps_verbose;
-extern int current_gps_speed;
-
-
-int read_gps_nmea(int *fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info, nmeaPARSER *parser)
-{
- int ret = 1;
- char c;
- int start_flag = 0;
- int found_cr = 0;
- int rx_count = 0;
- int gpsRxOverflow = 0;
-
- struct pollfd fds;
- fds.fd = *fd;
- fds.events = POLLIN;
-
- // NMEA or SINGLE-SENTENCE GPS mode
-
-
- while (1) {
- //check if the thread should terminate
- if (terminate_gps_thread == true) {
-// printf("terminate_gps_thread=%u ", terminate_gps_thread);
-// printf("exiting mtk thread\n");
-// fflush(stdout);
- ret = 2;
- break;
- }
-
- if (poll(&fds, 1, 1000) > 0) {
- if (read(*fd, &c, 1) > 0) {
- // detect start while acquiring stream
- // printf("Char = %c\n", c);
- if (!start_flag && (c == '$')) {
- start_flag = 1;
- found_cr = 0;
- rx_count = 0;
-
- } else if (!start_flag) { // keep looking for start sign
- continue;
- }
-
- if (rx_count >= buffer_size) {
- // The buffer is already full and we haven't found a valid NMEA sentence.
- // Flush the buffer and note the overflow event.
- gpsRxOverflow++;
- start_flag = 0;
- found_cr = 0;
- rx_count = 0;
-
- if (gps_verbose) printf("\t[gps] Buffer full\n");
-
- } else {
- // store chars in buffer
- gps_rx_buffer[rx_count] = c;
- rx_count++;
- }
-
- // look for carriage return CR
- if (start_flag && c == 0x0d) {
- found_cr = 1;
- }
-
- // and then look for line feed LF
- if (start_flag && found_cr && c == 0x0a) {
- // parse one NMEA line, use buffer up to rx_count
- if (nmea_parse(parser, gps_rx_buffer, rx_count, info) > 0) {
- ret = 0;
- }
-
- break;
- }
-
- } else {
- break;
- }
-
- } else {
- break;
- }
- }
-
-
-
- // As soon as one NMEA message has been parsed, we break out of the loop and end here
- return(ret);
-}
-
-
-/**
- * \brief Convert NDEG (NMEA degree) to fractional degree
- */
-float ndeg2degree(float val)
-{
- float deg = ((int)(val / 100));
- val = deg + (val - deg * 100) / 60;
- return val;
-}
-
-void *nmea_loop(void *args)
-{
- /* Set thread name */
- prctl(PR_SET_NAME, "gps nmea read", getpid());
-
- /* Retrieve file descriptor and thread flag */
- struct arg_struct *arguments = (struct arg_struct *)args;
- int *fd = arguments->fd_ptr;
- bool *thread_should_exit = arguments->thread_should_exit_ptr;
-
- /* Initialize gps stuff */
- nmeaINFO info_d;
- nmeaINFO *info = &info_d;
- char gps_rx_buffer[NMEA_BUFFER_SIZE];
-
- /* gps parser (nmea) */
- nmeaPARSER parser;
- nmea_parser_init(&parser);
- nmea_zero_INFO(info);
-
- /* advertise GPS topic */
- struct vehicle_gps_position_s nmea_gps_d = {.counter=0};
- nmea_gps = &nmea_gps_d;
- orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), nmea_gps);
-
- while (!(*thread_should_exit)) {
- /* Parse a message from the gps receiver */
- uint8_t read_res = read_gps_nmea(fd, gps_rx_buffer, NMEA_BUFFER_SIZE, info, &parser);
-
- if (0 == read_res) {
-
- /* convert data, ready it for publishing */
-
- /* convert nmea utc time to usec */
- struct tm timeinfo;
- timeinfo.tm_year = info->utc.year;
- timeinfo.tm_mon = info->utc.mon;
- timeinfo.tm_mday = info->utc.day;
- timeinfo.tm_hour = info->utc.hour;
- timeinfo.tm_min = info->utc.min;
- timeinfo.tm_sec = info->utc.sec;
-
- time_t epoch = mktime(&timeinfo);
-
- // printf("%d.%d.%d %d:%d:%d:%d\n", timeinfo.tm_year, timeinfo.tm_mon, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec, info->utc.hsec);
-
- nmea_gps->timestamp = hrt_absolute_time();
- nmea_gps->time_gps_usec = (uint64_t)((epoch)*1000000 + (info->utc.hsec)*10000);
- nmea_gps->fix_type = (uint8_t)info->fix;
- nmea_gps->lat = (int32_t)(ndeg2degree(info->lat) * 1e7f);
- nmea_gps->lon = (int32_t)(ndeg2degree(info->lon) * 1e7f);
- nmea_gps->alt = (int32_t)(info->elv * 1000.0f);
- nmea_gps->eph = (uint16_t)(info->HDOP * 100); //TODO:test scaling
- nmea_gps->epv = (uint16_t)(info->VDOP * 100); //TODO:test scaling
- nmea_gps->vel = (uint16_t)(info->speed * 1000 / 36); //*1000/3600*100
- nmea_gps->cog = (uint16_t)info->direction*100; //nmea: degrees float, ubx/mavlink: degrees*1e2
- nmea_gps->satellites_visible = (uint8_t)info->satinfo.inview;
-
- int i = 0;
-
- /* Write info about individual satellites */
- for (i = 0; i < 12; i++) {
- nmea_gps->satellite_prn[i] = (uint8_t)info->satinfo.sat[i].id;
- nmea_gps->satellite_used[i] = (uint8_t)info->satinfo.sat[i].in_use;
- nmea_gps->satellite_elevation[i] = (uint8_t)info->satinfo.sat[i].elv;
- nmea_gps->satellite_azimuth[i] = (uint8_t)info->satinfo.sat[i].azimuth;
- nmea_gps->satellite_snr[i] = (uint8_t)info->satinfo.sat[i].sig;
- }
-
- if (nmea_gps->satellites_visible > 0) {
- nmea_gps->satellite_info_available = 1;
-
- } else {
- nmea_gps->satellite_info_available = 0;
- }
-
- nmea_gps->counter_pos_valid++;
-
- nmea_gps->timestamp = hrt_absolute_time();
- nmea_gps->counter++;
-
- pthread_mutex_lock(nmea_mutex);
- nmea_state->last_message_timestamp = hrt_absolute_time();
- pthread_mutex_unlock(nmea_mutex);
-
- /* publish new GPS position */
- orb_publish(ORB_ID(vehicle_gps_position), gps_handle, nmea_gps);
-
- } else if (read_res == 2) { //termination
- /* de-advertise */
- close(gps_handle);
- break;
- }
-
- }
-
- //destroy gps parser
- nmea_parser_destroy(&parser);
- if(gps_verbose) printf("[gps] nmea loop is going to terminate\n");
- return NULL;
-
-}
-
-void *nmea_watchdog_loop(void *args)
-{
- /* Set thread name */
- prctl(PR_SET_NAME, "gps nmea watchdog", getpid());
-
- bool nmea_healthy = false;
-
- uint8_t nmea_fail_count = 0;
- uint8_t nmea_success_count = 0;
- bool once_ok = false;
-
- /* Retrieve file descriptor and thread flag */
- struct arg_struct *arguments = (struct arg_struct *)args;
- //int *fd = arguments->fd_ptr;
- bool *thread_should_exit = arguments->thread_should_exit_ptr;
-
- int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
- while (!(*thread_should_exit)) {
-// printf("nmea_watchdog_loop : while ");
- /* if we have no update for a long time print warning (in nmea mode there is no reconfigure) */
- pthread_mutex_lock(nmea_mutex);
- uint64_t timestamp_now = hrt_absolute_time();
- bool all_okay = true;
-
- if (timestamp_now - nmea_state->last_message_timestamp > NMEA_WATCHDOG_CRITICAL_TIME_MICROSECONDS) {
- all_okay = false;
- }
-
- pthread_mutex_unlock(nmea_mutex);
-
- if (!all_okay) {
- /* gps error */
- nmea_fail_count++;
-// printf("nmea error, nmea_fail_count=%u\n", nmea_fail_count);
-// fflush(stdout);
-
- /* If we have too many failures and another mode or baud should be tried, exit... */
- if ((gps_mode_try_all == true || gps_baud_try_all == true) && (nmea_fail_count >= NMEA_HEALTH_FAIL_COUNTER_LIMIT) && (nmea_healthy == false) && once_ok == false) {
- if (gps_verbose) printf("\t[gps] no NMEA module found\n");
-
- gps_mode_success = false;
- break;
- }
-
- if (nmea_healthy && nmea_fail_count >= NMEA_HEALTH_FAIL_COUNTER_LIMIT) {
- printf("\t[gps] ERROR: NMEA GPS module stopped responding\n");
- // global_data_send_subsystem_info(&nmea_present_enabled);
- mavlink_log_critical(mavlink_fd, "[gps] NMEA module stopped responding\n");
- nmea_healthy = false;
- nmea_success_count = 0;
-
- }
-
-
-
- fflush(stdout);
- sleep(1);
-
- } else {
- /* gps healthy */
-// printf("\t[gps] nmea success\n");
- nmea_success_count++;
-
- if (!nmea_healthy && nmea_success_count >= NMEA_HEALTH_SUCCESS_COUNTER_LIMIT) {
- printf("[gps] NMEA module found, status ok (baud=%d)\r\n", current_gps_speed);
- // global_data_send_subsystem_info(&nmea_present_enabled_healthy);
- mavlink_log_info(mavlink_fd, "[gps] NMEA module found, status ok\n");
- nmea_healthy = true;
- nmea_fail_count = 0;
- once_ok = true;
- }
-
- }
-
- usleep(NMEA_WATCHDOG_WAIT_TIME_MICROSECONDS);
- }
- if(gps_verbose) printf("[gps] nmea watchdog loop is going to terminate\n");
- close(mavlink_fd);
- return NULL;
-}
diff --git a/apps/gps/nmea_helper.h b/apps/gps/nmea_helper.h
deleted file mode 100644
index 3a853dd13..000000000
--- a/apps/gps/nmea_helper.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * nmea_helper.h
- *
- * Created on: Mar 15, 2012
- * Author: thomasgubler
- */
-
-#ifndef NMEA_H_
-#define NMEA_H_
-
-#include <stdint.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdio.h>
-#include "nmealib/nmea/nmea.h"
-
-
-//definitions for watchdog
-#define NMEA_WATCHDOG_CRITICAL_TIME_MICROSECONDS 2000000
-#define NMEA_WATCHDOG_WAIT_TIME_MICROSECONDS 800000
-
-typedef struct {
- uint64_t last_message_timestamp;
-} __attribute__((__packed__)) type_gps_bin_nmea_state;
-
-typedef type_gps_bin_nmea_state gps_bin_nmea_state_t;
-
-extern gps_bin_nmea_state_t *nmea_state;
-extern pthread_mutex_t *nmea_mutex;
-
-
-
-int read_gps_nmea(int *fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info, nmeaPARSER *parser);
-
-void *nmea_loop(void *arg);
-
-void *nmea_watchdog_loop(void *arg);
-
-/**
- * \brief Convert NDEG (NMEA degree) to fractional degree
- */
-float ndeg2degree(float val);
-
-void nmea_init(void);
-
-
-#endif /* NMEA_H_ */
diff --git a/apps/gps/nmealib/LICENSE.TXT b/apps/gps/nmealib/LICENSE.TXT
deleted file mode 100644
index 807db7916..000000000
--- a/apps/gps/nmealib/LICENSE.TXT
+++ /dev/null
@@ -1,506 +0,0 @@
- GNU LESSER GENERAL PUBLIC LICENSE
- Version 2.1, February 1999
-
- Copyright (C) 1991, 1999 Free Software Foundation, Inc.
- 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- Everyone is permitted to copy and distribute verbatim copies
- of this license document, but changing it is not allowed.
-
-[This is the first released version of the Lesser GPL. It also counts
- as the successor of the GNU Library Public License, version 2, hence
- the version number 2.1.]
-
- Preamble
-
- The licenses for most software are designed to take away your
-freedom to share and change it. By contrast, the GNU General Public
-Licenses are intended to guarantee your freedom to share and change
-free software--to make sure the software is free for all its users.
-
- This license, the Lesser General Public License, applies to some
-specially designated software packages--typically libraries--of the
-Free Software Foundation and other authors who decide to use it. You
-can use it too, but we suggest you first think carefully about whether
-this license or the ordinary General Public License is the better
-strategy to use in any particular case, based on the explanations below.
-
- When we speak of free software, we are referring to freedom of use,
-not price. Our General Public Licenses are designed to make sure that
-you have the freedom to distribute copies of free software (and charge
-for this service if you wish); that you receive source code or can get
-it if you want it; that you can change the software and use pieces of
-it in new free programs; and that you are informed that you can do
-these things.
-
- To protect your rights, we need to make restrictions that forbid
-distributors to deny you these rights or to ask you to surrender these
-rights. These restrictions translate to certain responsibilities for
-you if you distribute copies of the library or if you modify it.
-
- For example, if you distribute copies of the library, whether gratis
-or for a fee, you must give the recipients all the rights that we gave
-you. You must make sure that they, too, receive or can get the source
-code. If you link other code with the library, you must provide
-complete object files to the recipients, so that they can relink them
-with the library after making changes to the library and recompiling
-it. And you must show them these terms so they know their rights.
-
- We protect your rights with a two-step method: (1) we copyright the
-library, and (2) we offer you this license, which gives you legal
-permission to copy, distribute and/or modify the library.
-
- To protect each distributor, we want to make it very clear that
-there is no warranty for the free library. Also, if the library is
-modified by someone else and passed on, the recipients should know
-that what they have is not the original version, so that the original
-author's reputation will not be affected by problems that might be
-introduced by others.
-
- Finally, software patents pose a constant threat to the existence of
-any free program. We wish to make sure that a company cannot
-effectively restrict the users of a free program by obtaining a
-restrictive license from a patent holder. Therefore, we insist that
-any patent license obtained for a version of the library must be
-consistent with the full freedom of use specified in this license.
-
- Most GNU software, including some libraries, is covered by the
-ordinary GNU General Public License. This license, the GNU Lesser
-General Public License, applies to certain designated libraries, and
-is quite different from the ordinary General Public License. We use
-this license for certain libraries in order to permit linking those
-libraries into non-free programs.
-
- When a program is linked with a library, whether statically or using
-a shared library, the combination of the two is legally speaking a
-combined work, a derivative of the original library. The ordinary
-General Public License therefore permits such linking only if the
-entire combination fits its criteria of freedom. The Lesser General
-Public License permits more lax criteria for linking other code with
-the library.
-
- We call this license the "Lesser" General Public License because it
-does Less to protect the user's freedom than the ordinary General
-Public License. It also provides other free software developers Less
-of an advantage over competing non-free programs. These disadvantages
-are the reason we use the ordinary General Public License for many
-libraries. However, the Lesser license provides advantages in certain
-special circumstances.
-
- For example, on rare occasions, there may be a special need to
-encourage the widest possible use of a certain library, so that it becomes
-a de-facto standard. To achieve this, non-free programs must be
-allowed to use the library. A more frequent case is that a free
-library does the same job as widely used non-free libraries. In this
-case, there is little to gain by limiting the free library to free
-software only, so we use the Lesser General Public License.
-
- In other cases, permission to use a particular library in non-free
-programs enables a greater number of people to use a large body of
-free software. For example, permission to use the GNU C Library in
-non-free programs enables many more people to use the whole GNU
-operating system, as well as its variant, the GNU/Linux operating
-system.
-
- Although the Lesser General Public License is Less protective of the
-users' freedom, it does ensure that the user of a program that is
-linked with the Library has the freedom and the wherewithal to run
-that program using a modified version of the Library.
-
- The precise terms and conditions for copying, distribution and
-modification follow. Pay close attention to the difference between a
-"work based on the library" and a "work that uses the library". The
-former contains code derived from the library, whereas the latter must
-be combined with the library in order to run.
-
- GNU LESSER GENERAL PUBLIC LICENSE
- TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
-
- 0. This License Agreement applies to any software library or other
-program which contains a notice placed by the copyright holder or
-other authorized party saying it may be distributed under the terms of
-this Lesser General Public License (also called "this License").
-Each licensee is addressed as "you".
-
- A "library" means a collection of software functions and/or data
-prepared so as to be conveniently linked with application programs
-(which use some of those functions and data) to form executables.
-
- The "Library", below, refers to any such software library or work
-which has been distributed under these terms. A "work based on the
-Library" means either the Library or any derivative work under
-copyright law: that is to say, a work containing the Library or a
-portion of it, either verbatim or with modifications and/or translated
-straightforwardly into another language. (Hereinafter, translation is
-included without limitation in the term "modification".)
-
- "Source code" for a work means the preferred form of the work for
-making modifications to it. For a library, complete source code means
-all the source code for all modules it contains, plus any associated
-interface definition files, plus the scripts used to control compilation
-and installation of the library.
-
- Activities other than copying, distribution and modification are not
-covered by this License; they are outside its scope. The act of
-running a program using the Library is not restricted, and output from
-such a program is covered only if its contents constitute a work based
-on the Library (independent of the use of the Library in a tool for
-writing it). Whether that is true depends on what the Library does
-and what the program that uses the Library does.
-
- 1. You may copy and distribute verbatim copies of the Library's
-complete source code as you receive it, in any medium, provided that
-you conspicuously and appropriately publish on each copy an
-appropriate copyright notice and disclaimer of warranty; keep intact
-all the notices that refer to this License and to the absence of any
-warranty; and distribute a copy of this License along with the
-Library.
-
- You may charge a fee for the physical act of transferring a copy,
-and you may at your option offer warranty protection in exchange for a
-fee.
-
- 2. You may modify your copy or copies of the Library or any portion
-of it, thus forming a work based on the Library, and copy and
-distribute such modifications or work under the terms of Section 1
-above, provided that you also meet all of these conditions:
-
- a) The modified work must itself be a software library.
-
- b) You must cause the files modified to carry prominent notices
- stating that you changed the files and the date of any change.
-
- c) You must cause the whole of the work to be licensed at no
- charge to all third parties under the terms of this License.
-
- d) If a facility in the modified Library refers to a function or a
- table of data to be supplied by an application program that uses
- the facility, other than as an argument passed when the facility
- is invoked, then you must make a good faith effort to ensure that,
- in the event an application does not supply such function or
- table, the facility still operates, and performs whatever part of
- its purpose remains meaningful.
-
- (For example, a function in a library to compute square roots has
- a purpose that is entirely well-defined independent of the
- application. Therefore, Subsection 2d requires that any
- application-supplied function or table used by this function must
- be optional: if the application does not supply it, the square
- root function must still compute square roots.)
-
-These requirements apply to the modified work as a whole. If
-identifiable sections of that work are not derived from the Library,
-and can be reasonably considered independent and separate works in
-themselves, then this License, and its terms, do not apply to those
-sections when you distribute them as separate works. But when you
-distribute the same sections as part of a whole which is a work based
-on the Library, the distribution of the whole must be on the terms of
-this License, whose permissions for other licensees extend to the
-entire whole, and thus to each and every part regardless of who wrote
-it.
-
-Thus, it is not the intent of this section to claim rights or contest
-your rights to work written entirely by you; rather, the intent is to
-exercise the right to control the distribution of derivative or
-collective works based on the Library.
-
-In addition, mere aggregation of another work not based on the Library
-with the Library (or with a work based on the Library) on a volume of
-a storage or distribution medium does not bring the other work under
-the scope of this License.
-
- 3. You may opt to apply the terms of the ordinary GNU General Public
-License instead of this License to a given copy of the Library. To do
-this, you must alter all the notices that refer to this License, so
-that they refer to the ordinary GNU General Public License, version 2,
-instead of to this License. (If a newer version than version 2 of the
-ordinary GNU General Public License has appeared, then you can specify
-that version instead if you wish.) Do not make any other change in
-these notices.
-
- Once this change is made in a given copy, it is irreversible for
-that copy, so the ordinary GNU General Public License applies to all
-subsequent copies and derivative works made from that copy.
-
- This option is useful when you wish to copy part of the code of
-the Library into a program that is not a library.
-
- 4. You may copy and distribute the Library (or a portion or
-derivative of it, under Section 2) in object code or executable form
-under the terms of Sections 1 and 2 above provided that you accompany
-it with the complete corresponding machine-readable source code, which
-must be distributed under the terms of Sections 1 and 2 above on a
-medium customarily used for software interchange.
-
- If distribution of object code is made by offering access to copy
-from a designated place, then offering equivalent access to copy the
-source code from the same place satisfies the requirement to
-distribute the source code, even though third parties are not
-compelled to copy the source along with the object code.
-
- 5. A program that contains no derivative of any portion of the
-Library, but is designed to work with the Library by being compiled or
-linked with it, is called a "work that uses the Library". Such a
-work, in isolation, is not a derivative work of the Library, and
-therefore falls outside the scope of this License.
-
- However, linking a "work that uses the Library" with the Library
-creates an executable that is a derivative of the Library (because it
-contains portions of the Library), rather than a "work that uses the
-library". The executable is therefore covered by this License.
-Section 6 states terms for distribution of such executables.
-
- When a "work that uses the Library" uses material from a header file
-that is part of the Library, the object code for the work may be a
-derivative work of the Library even though the source code is not.
-Whether this is true is especially significant if the work can be
-linked without the Library, or if the work is itself a library. The
-threshold for this to be true is not precisely defined by law.
-
- If such an object file uses only numerical parameters, data
-structure layouts and accessors, and small macros and small inline
-functions (ten lines or less in length), then the use of the object
-file is unrestricted, regardless of whether it is legally a derivative
-work. (Executables containing this object code plus portions of the
-Library will still fall under Section 6.)
-
- Otherwise, if the work is a derivative of the Library, you may
-distribute the object code for the work under the terms of Section 6.
-Any executables containing that work also fall under Section 6,
-whether or not they are linked directly with the Library itself.
-
- 6. As an exception to the Sections above, you may also combine or
-link a "work that uses the Library" with the Library to produce a
-work containing portions of the Library, and distribute that work
-under terms of your choice, provided that the terms permit
-modification of the work for the customer's own use and reverse
-engineering for debugging such modifications.
-
- You must give prominent notice with each copy of the work that the
-Library is used in it and that the Library and its use are covered by
-this License. You must supply a copy of this License. If the work
-during execution displays copyright notices, you must include the
-copyright notice for the Library among them, as well as a reference
-directing the user to the copy of this License. Also, you must do one
-of these things:
-
- a) Accompany the work with the complete corresponding
- machine-readable source code for the Library including whatever
- changes were used in the work (which must be distributed under
- Sections 1 and 2 above); and, if the work is an executable linked
- with the Library, with the complete machine-readable "work that
- uses the Library", as object code and/or source code, so that the
- user can modify the Library and then relink to produce a modified
- executable containing the modified Library. (It is understood
- that the user who changes the contents of definitions files in the
- Library will not necessarily be able to recompile the application
- to use the modified definitions.)
-
- b) Use a suitable shared library mechanism for linking with the
- Library. A suitable mechanism is one that (1) uses at run time a
- copy of the library already present on the user's computer system,
- rather than copying library functions into the executable, and (2)
- will operate properly with a modified version of the library, if
- the user installs one, as long as the modified version is
- interface-compatible with the version that the work was made with.
-
- c) Accompany the work with a written offer, valid for at
- least three years, to give the same user the materials
- specified in Subsection 6a, above, for a charge no more
- than the cost of performing this distribution.
-
- d) If distribution of the work is made by offering access to copy
- from a designated place, offer equivalent access to copy the above
- specified materials from the same place.
-
- e) Verify that the user has already received a copy of these
- materials or that you have already sent this user a copy.
-
- For an executable, the required form of the "work that uses the
-Library" must include any data and utility programs needed for
-reproducing the executable from it. However, as a special exception,
-the materials to be distributed need not include anything that is
-normally distributed (in either source or binary form) with the major
-components (compiler, kernel, and so on) of the operating system on
-which the executable runs, unless that component itself accompanies
-the executable.
-
- It may happen that this requirement contradicts the license
-restrictions of other proprietary libraries that do not normally
-accompany the operating system. Such a contradiction means you cannot
-use both them and the Library together in an executable that you
-distribute.
-
- 7. You may place library facilities that are a work based on the
-Library side-by-side in a single library together with other library
-facilities not covered by this License, and distribute such a combined
-library, provided that the separate distribution of the work based on
-the Library and of the other library facilities is otherwise
-permitted, and provided that you do these two things:
-
- a) Accompany the combined library with a copy of the same work
- based on the Library, uncombined with any other library
- facilities. This must be distributed under the terms of the
- Sections above.
-
- b) Give prominent notice with the combined library of the fact
- that part of it is a work based on the Library, and explaining
- where to find the accompanying uncombined form of the same work.
-
- 8. You may not copy, modify, sublicense, link with, or distribute
-the Library except as expressly provided under this License. Any
-attempt otherwise to copy, modify, sublicense, link with, or
-distribute the Library is void, and will automatically terminate your
-rights under this License. However, parties who have received copies,
-or rights, from you under this License will not have their licenses
-terminated so long as such parties remain in full compliance.
-
- 9. You are not required to accept this License, since you have not
-signed it. However, nothing else grants you permission to modify or
-distribute the Library or its derivative works. These actions are
-prohibited by law if you do not accept this License. Therefore, by
-modifying or distributing the Library (or any work based on the
-Library), you indicate your acceptance of this License to do so, and
-all its terms and conditions for copying, distributing or modifying
-the Library or works based on it.
-
- 10. Each time you redistribute the Library (or any work based on the
-Library), the recipient automatically receives a license from the
-original licensor to copy, distribute, link with or modify the Library
-subject to these terms and conditions. You may not impose any further
-restrictions on the recipients' exercise of the rights granted herein.
-You are not responsible for enforcing compliance by third parties with
-this License.
-
- 11. If, as a consequence of a court judgment or allegation of patent
-infringement or for any other reason (not limited to patent issues),
-conditions are imposed on you (whether by court order, agreement or
-otherwise) that contradict the conditions of this License, they do not
-excuse you from the conditions of this License. If you cannot
-distribute so as to satisfy simultaneously your obligations under this
-License and any other pertinent obligations, then as a consequence you
-may not distribute the Library at all. For example, if a patent
-license would not permit royalty-free redistribution of the Library by
-all those who receive copies directly or indirectly through you, then
-the only way you could satisfy both it and this License would be to
-refrain entirely from distribution of the Library.
-
-If any portion of this section is held invalid or unenforceable under any
-particular circumstance, the balance of the section is intended to apply,
-and the section as a whole is intended to apply in other circumstances.
-
-It is not the purpose of this section to induce you to infringe any
-patents or other property right claims or to contest validity of any
-such claims; this section has the sole purpose of protecting the
-integrity of the free software distribution system which is
-implemented by public license practices. Many people have made
-generous contributions to the wide range of software distributed
-through that system in reliance on consistent application of that
-system; it is up to the author/donor to decide if he or she is willing
-to distribute software through any other system and a licensee cannot
-impose that choice.
-
-This section is intended to make thoroughly clear what is believed to
-be a consequence of the rest of this License.
-
- 12. If the distribution and/or use of the Library is restricted in
-certain countries either by patents or by copyrighted interfaces, the
-original copyright holder who places the Library under this License may add
-an explicit geographical distribution limitation excluding those countries,
-so that distribution is permitted only in or among countries not thus
-excluded. In such case, this License incorporates the limitation as if
-written in the body of this License.
-
- 13. The Free Software Foundation may publish revised and/or new
-versions of the Lesser General Public License from time to time.
-Such new versions will be similar in spirit to the present version,
-but may differ in detail to address new problems or concerns.
-
-Each version is given a distinguishing version number. If the Library
-specifies a version number of this License which applies to it and
-"any later version", you have the option of following the terms and
-conditions either of that version or of any later version published by
-the Free Software Foundation. If the Library does not specify a
-license version number, you may choose any version ever published by
-the Free Software Foundation.
-
- 14. If you wish to incorporate parts of the Library into other free
-programs whose distribution conditions are incompatible with these,
-write to the author to ask for permission. For software which is
-copyrighted by the Free Software Foundation, write to the Free
-Software Foundation; we sometimes make exceptions for this. Our
-decision will be guided by the two goals of preserving the free status
-of all derivatives of our free software and of promoting the sharing
-and reuse of software generally.
-
- NO WARRANTY
-
- 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO
-WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.
-EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR
-OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY
-KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE
-IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
-PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE
-LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME
-THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
-
- 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN
-WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY
-AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU
-FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR
-CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE
-LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING
-RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A
-FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF
-SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
-DAMAGES.
-
- END OF TERMS AND CONDITIONS
-
- How to Apply These Terms to Your New Libraries
-
- If you develop a new library, and you want it to be of the greatest
-possible use to the public, we recommend making it free software that
-everyone can redistribute and change. You can do so by permitting
-redistribution under these terms (or, alternatively, under the terms of the
-ordinary General Public License).
-
- To apply these terms, attach the following notices to the library. It is
-safest to attach them to the start of each source file to most effectively
-convey the exclusion of warranty; and each file should have at least the
-"copyright" line and a pointer to where the full notice is found.
-
- <one line to give the library's name and a brief idea of what it does.>
- Copyright (C) <year> <name of author>
-
- This library is free software; you can redistribute it and/or
- modify it under the terms of the GNU Lesser General Public
- License as published by the Free Software Foundation; either
- version 2.1 of the License, or (at your option) any later version.
-
- This library is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- Lesser General Public License for more details.
-
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
-
-Also add information on how to contact you by electronic and paper mail.
-
-You should also get your employer (if you work as a programmer) or your
-school, if any, to sign a "copyright disclaimer" for the library, if
-necessary. Here is a sample; alter the names:
-
- Yoyodyne, Inc., hereby disclaims all copyright interest in the
- library `Frob' (a library for tweaking knobs) written by James Random Hacker.
-
- <signature of Ty Coon>, 1 April 1990
- Ty Coon, President of Vice
-
-That's all there is to it!
-
-
-
-
diff --git a/apps/gps/nmealib/README.TXT b/apps/gps/nmealib/README.TXT
deleted file mode 100644
index 8ede6a036..000000000
--- a/apps/gps/nmealib/README.TXT
+++ /dev/null
@@ -1,26 +0,0 @@
-NMEA library see: http://nmea.sourceforge.net/
-
-Disclaimer
-
-The National Marine Electronics Association (NMEA) has developed a specification that defines the interface between various pieces of marine electronic equipment. The standard permits marine electronics to send information to computers and to other marine equipment.
-Most computer programs that provide real time position information understand and expect data to be in NMEA format. This data includes the complete PVT (position, velocity, time) solution computed by the GPS receiver. The idea of NMEA is to send a line of data called a sentence that is totally self contained and independent from other sentences. All NMEA sentences is sequences of ACSII symbols begins with a '$' and ends with a carriage return/line feed sequence and can be no longer than 80 characters of visible text (plus the line terminators).
-
-Introduction
-
-We present library in 'C' programming language for work with NMEA protocol. Small and easy to use. The library build on different compilers under different platforms (see below). The code was tested in real projects. Just download and try...
-
-Features
-
-- Analysis NMEA sentences and granting GPS data in C structures
-- Generate NMEA sentences
-- Supported sentences: GPGGA, GPGSA, GPGSV, GPRMC, GPVTG
-- Multilevel architecture of algorithms
-- Additional functions of geographical mathematics and work with navigation data
-
-Supported (tested) platforms
-
-- Microsoft Windows (MS Visual Studio 8.0, GCC)
-- Windows Mobile, Windows CE (MS Visual Studio 8.0)
-- UNIX (GCC)
-
-Licence: LGPL
diff --git a/apps/gps/nmealib/context.c b/apps/gps/nmealib/context.c
deleted file mode 100644
index 6ee2f5ad3..000000000
--- a/apps/gps/nmealib/context.c
+++ /dev/null
@@ -1,67 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: context.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#include "nmea/context.h"
-
-#include <string.h>
-#include <stdarg.h>
-#include <stdio.h>
-
-nmeaPROPERTY * nmea_property(void)
-{
- static nmeaPROPERTY prop = {
- 0, 0, NMEA_DEF_PARSEBUFF
- };
-
- return &prop;
-}
-
-void nmea_trace(const char *str, ...)
-{
- int size;
- va_list arg_list;
- char buff[NMEA_DEF_PARSEBUFF];
- nmeaTraceFunc func = nmea_property()->trace_func;
-
- if(func)
- {
- va_start(arg_list, str);
- size = NMEA_POSIX(vsnprintf)(&buff[0], NMEA_DEF_PARSEBUFF - 1, str, arg_list);
- va_end(arg_list);
-
- if(size > 0)
- (*func)(&buff[0], size);
- }
-}
-
-void nmea_trace_buff(const char *buff, int buff_size)
-{
- nmeaTraceFunc func = nmea_property()->trace_func;
- if(func && buff_size)
- (*func)(buff, buff_size);
-}
-
-void nmea_error(const char *str, ...)
-{
- int size;
- va_list arg_list;
- char buff[NMEA_DEF_PARSEBUFF];
- nmeaErrorFunc func = nmea_property()->error_func;
-
- if(func)
- {
- va_start(arg_list, str);
- size = NMEA_POSIX(vsnprintf)(&buff[0], NMEA_DEF_PARSEBUFF - 1, str, arg_list);
- va_end(arg_list);
-
- if(size > 0)
- (*func)(&buff[0], size);
- }
-}
diff --git a/apps/gps/nmealib/generate.c b/apps/gps/nmealib/generate.c
deleted file mode 100644
index 4c9389300..000000000
--- a/apps/gps/nmealib/generate.c
+++ /dev/null
@@ -1,229 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: generate.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#include "nmea/tok.h"
-#include "nmea/sentence.h"
-#include "nmea/generate.h"
-#include "nmea/units.h"
-
-#include <string.h>
-#include <stdlib.h>
-#include <math.h>
-
-int nmea_gen_GPGGA(char *buff, int buff_sz, nmeaGPGGA *pack)
-{
- return nmea_printf(buff, buff_sz,
- "$GPGGA,%02d%02d%02d.%02d,%07.4f,%C,%07.4f,%C,%1d,%02d,%03.1f,%03.1f,%C,%03.1f,%C,%03.1f,%04d",
- pack->utc.hour, pack->utc.min, pack->utc.sec, pack->utc.hsec,
- pack->lat, pack->ns, pack->lon, pack->ew,
- pack->sig, pack->satinuse, pack->HDOP, pack->elv, pack->elv_units,
- pack->diff, pack->diff_units, pack->dgps_age, pack->dgps_sid);
-}
-
-int nmea_gen_GPGSA(char *buff, int buff_sz, nmeaGPGSA *pack)
-{
- return nmea_printf(buff, buff_sz,
- "$GPGSA,%C,%1d,%02d,%02d,%02d,%02d,%02d,%02d,%02d,%02d,%02d,%02d,%02d,%02d,%03.1f,%03.1f,%03.1f",
- pack->fix_mode, pack->fix_type,
- pack->sat_prn[0], pack->sat_prn[1], pack->sat_prn[2], pack->sat_prn[3], pack->sat_prn[4], pack->sat_prn[5],
- pack->sat_prn[6], pack->sat_prn[7], pack->sat_prn[8], pack->sat_prn[9], pack->sat_prn[10], pack->sat_prn[11],
- pack->PDOP, pack->HDOP, pack->VDOP);
-}
-
-int nmea_gen_GPGSV(char *buff, int buff_sz, nmeaGPGSV *pack)
-{
- return nmea_printf(buff, buff_sz,
- "$GPGSV,%1d,%1d,%02d,"
- "%02d,%02d,%03d,%02d,"
- "%02d,%02d,%03d,%02d,"
- "%02d,%02d,%03d,%02d,"
- "%02d,%02d,%03d,%02d",
- pack->pack_count, pack->pack_index + 1, pack->sat_count,
- pack->sat_data[0].id, pack->sat_data[0].elv, pack->sat_data[0].azimuth, pack->sat_data[0].sig,
- pack->sat_data[1].id, pack->sat_data[1].elv, pack->sat_data[1].azimuth, pack->sat_data[1].sig,
- pack->sat_data[2].id, pack->sat_data[2].elv, pack->sat_data[2].azimuth, pack->sat_data[2].sig,
- pack->sat_data[3].id, pack->sat_data[3].elv, pack->sat_data[3].azimuth, pack->sat_data[3].sig);
-}
-
-int nmea_gen_GPRMC(char *buff, int buff_sz, nmeaGPRMC *pack)
-{
- return nmea_printf(buff, buff_sz,
- "$GPRMC,%02d%02d%02d.%02d,%C,%07.4f,%C,%07.4f,%C,%03.1f,%03.1f,%02d%02d%02d,%03.1f,%C,%C",
- pack->utc.hour, pack->utc.min, pack->utc.sec, pack->utc.hsec,
- pack->status, pack->lat, pack->ns, pack->lon, pack->ew,
- pack->speed, pack->direction,
- pack->utc.day, pack->utc.mon + 1, pack->utc.year - 100,
- pack->declination, pack->declin_ew, pack->mode);
-}
-
-int nmea_gen_GPVTG(char *buff, int buff_sz, nmeaGPVTG *pack)
-{
- return nmea_printf(buff, buff_sz,
- "$GPVTG,%.1f,%C,%.1f,%C,%.1f,%C,%.1f,%C",
- pack->dir, pack->dir_t,
- pack->dec, pack->dec_m,
- pack->spn, pack->spn_n,
- pack->spk, pack->spk_k);
-}
-
-void nmea_info2GPGGA(const nmeaINFO *info, nmeaGPGGA *pack)
-{
- nmea_zero_GPGGA(pack);
-
- pack->utc = info->utc;
- pack->lat = fabs(info->lat);
- pack->ns = ((info->lat > 0)?'N':'S');
- pack->lon = fabs(info->lon);
- pack->ew = ((info->lon > 0)?'E':'W');
- pack->sig = info->sig;
- pack->satinuse = info->satinfo.inuse;
- pack->HDOP = info->HDOP;
- pack->elv = info->elv;
-}
-
-void nmea_info2GPGSA(const nmeaINFO *info, nmeaGPGSA *pack)
-{
- int it;
-
- nmea_zero_GPGSA(pack);
-
- pack->fix_type = info->fix;
- pack->PDOP = info->PDOP;
- pack->HDOP = info->HDOP;
- pack->VDOP = info->VDOP;
-
- for(it = 0; it < NMEA_MAXSAT; ++it)
- {
- pack->sat_prn[it] =
- ((info->satinfo.sat[it].in_use)?info->satinfo.sat[it].id:0);
- }
-}
-
-int nmea_gsv_npack(int sat_count)
-{
- int pack_count = (int)ceil(((float)sat_count) / NMEA_SATINPACK);
-
- if(0 == pack_count)
- pack_count = 1;
-
- return pack_count;
-}
-
-void nmea_info2GPGSV(const nmeaINFO *info, nmeaGPGSV *pack, int pack_idx)
-{
- int sit, pit;
-
- nmea_zero_GPGSV(pack);
-
- pack->sat_count = (info->satinfo.inview <= NMEA_MAXSAT)?info->satinfo.inview:NMEA_MAXSAT;
- pack->pack_count = nmea_gsv_npack(pack->sat_count);
-
- if(pack->pack_count == 0)
- pack->pack_count = 1;
-
- if(pack_idx >= pack->pack_count)
- pack->pack_index = pack_idx % pack->pack_count;
- else
- pack->pack_index = pack_idx;
-
- for(pit = 0, sit = pack->pack_index * NMEA_SATINPACK; pit < NMEA_SATINPACK; ++pit, ++sit)
- pack->sat_data[pit] = info->satinfo.sat[sit];
-}
-
-void nmea_info2GPRMC(const nmeaINFO *info, nmeaGPRMC *pack)
-{
- nmea_zero_GPRMC(pack);
-
- pack->utc = info->utc;
- pack->status = ((info->sig > 0)?'A':'V');
- pack->lat = fabs(info->lat);
- pack->ns = ((info->lat > 0)?'N':'S');
- pack->lon = fabs(info->lon);
- pack->ew = ((info->lon > 0)?'E':'W');
- pack->speed = info->speed / NMEA_TUD_KNOTS;
- pack->direction = info->direction;
- pack->declination = info->declination;
- pack->declin_ew = 'E';
- pack->mode = ((info->sig > 0)?'A':'N');
-}
-
-void nmea_info2GPVTG(const nmeaINFO *info, nmeaGPVTG *pack)
-{
- nmea_zero_GPVTG(pack);
-
- pack->dir = info->direction;
- pack->dec = info->declination;
- pack->spn = info->speed / NMEA_TUD_KNOTS;
- pack->spk = info->speed;
-}
-
-int nmea_generate(
- char *buff, int buff_sz,
- const nmeaINFO *info,
- int generate_mask
- )
-{
- int gen_count = 0, gsv_it, gsv_count;
- int pack_mask = generate_mask;
-
- nmeaGPGGA gga;
- nmeaGPGSA gsa;
- nmeaGPGSV gsv;
- nmeaGPRMC rmc;
- nmeaGPVTG vtg;
-
- if(!buff)
- return 0;
-
- while(pack_mask)
- {
- if(pack_mask & GPGGA)
- {
- nmea_info2GPGGA(info, &gga);
- gen_count += nmea_gen_GPGGA(buff + gen_count, buff_sz - gen_count, &gga);
- pack_mask &= ~GPGGA;
- }
- else if(pack_mask & GPGSA)
- {
- nmea_info2GPGSA(info, &gsa);
- gen_count += nmea_gen_GPGSA(buff + gen_count, buff_sz - gen_count, &gsa);
- pack_mask &= ~GPGSA;
- }
- else if(pack_mask & GPGSV)
- {
- gsv_count = nmea_gsv_npack(info->satinfo.inview);
- for(gsv_it = 0; gsv_it < gsv_count && buff_sz - gen_count > 0; ++gsv_it)
- {
- nmea_info2GPGSV(info, &gsv, gsv_it);
- gen_count += nmea_gen_GPGSV(buff + gen_count, buff_sz - gen_count, &gsv);
- }
- pack_mask &= ~GPGSV;
- }
- else if(pack_mask & GPRMC)
- {
- nmea_info2GPRMC(info, &rmc);
- gen_count += nmea_gen_GPRMC(buff + gen_count, buff_sz - gen_count, &rmc);
- pack_mask &= ~GPRMC;
- }
- else if(pack_mask & GPVTG)
- {
- nmea_info2GPVTG(info, &vtg);
- gen_count += nmea_gen_GPVTG(buff + gen_count, buff_sz - gen_count, &vtg);
- pack_mask &= ~GPVTG;
- }
- else
- break;
-
- if(buff_sz - gen_count <= 0)
- break;
- }
-
- return gen_count;
-}
diff --git a/apps/gps/nmealib/generator.c b/apps/gps/nmealib/generator.c
deleted file mode 100644
index ce40b0f1a..000000000
--- a/apps/gps/nmealib/generator.c
+++ /dev/null
@@ -1,399 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: generator.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#include "nmea/gmath.h"
-#include "nmea/generate.h"
-#include "nmea/generator.h"
-#include "nmea/context.h"
-
-#include <string.h>
-#include <stdlib.h>
-
-#if defined(NMEA_WIN) && defined(_MSC_VER)
-# pragma warning(disable: 4100) /* unreferenced formal parameter */
-#endif
-
-float nmea_random(float min, float max)
-{
- static float rand_max = MAX_RAND;//RAND_MAX; //nuttx defines MAX_RAND instead of RAND_MAX
- float rand_val = rand();
- float bounds = max - min;
- return min + (rand_val * bounds) / rand_max;
-}
-
-/*
- * low level
- */
-
-int nmea_gen_init(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- int RetVal = 1; int smask = info->smask;
- nmeaGENERATOR *igen = gen;
-
- nmea_zero_INFO(info);
- info->smask = smask;
-
- info->lat = NMEA_DEF_LAT;
- info->lon = NMEA_DEF_LON;
-
- while(RetVal && igen)
- {
- if(igen->init_call)
- RetVal = (*igen->init_call)(igen, info);
- igen = igen->next;
- }
-
- return RetVal;
-}
-
-int nmea_gen_loop(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- int RetVal = 1;
-
- if(gen->loop_call)
- RetVal = (*gen->loop_call)(gen, info);
-
- if(RetVal && gen->next)
- RetVal = nmea_gen_loop(gen->next, info);
-
- return RetVal;
-}
-
-int nmea_gen_reset(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- int RetVal = 1;
-
- if(gen->reset_call)
- RetVal = (*gen->reset_call)(gen, info);
-
- return RetVal;
-}
-
-void nmea_gen_destroy(nmeaGENERATOR *gen)
-{
- if(gen->next)
- {
- nmea_gen_destroy(gen->next);
- gen->next = 0;
- }
-
- if(gen->destroy_call)
- (*gen->destroy_call)(gen);
-
- free(gen);
-}
-
-void nmea_gen_add(nmeaGENERATOR *to, nmeaGENERATOR *gen)
-{
- if(to->next)
- nmea_gen_add(to->next, gen);
- else
- to->next = gen;
-}
-
-int nmea_generate_from(
- char *buff, int buff_sz,
- nmeaINFO *info,
- nmeaGENERATOR *gen,
- int generate_mask
- )
-{
- int retval;
-
- if(0 != (retval = nmea_gen_loop(gen, info)))
- retval = nmea_generate(buff, buff_sz, info, generate_mask);
-
- return retval;
-}
-
-/*
- * NOISE generator
- */
-
-int nmea_igen_noise_init(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- return 1;
-}
-
-int nmea_igen_noise_loop(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- int it;
- int in_use;
-
- info->sig = (int)nmea_random(1, 3);
- info->PDOP = nmea_random(0, 9);
- info->HDOP = nmea_random(0, 9);
- info->VDOP = nmea_random(0, 9);
- info->fix = (int)nmea_random(2, 3);
- info->lat = nmea_random(0, 100);
- info->lon = nmea_random(0, 100);
- info->speed = nmea_random(0, 100);
- info->direction = nmea_random(0, 360);
- info->declination = nmea_random(0, 360);
- info->elv = (int)nmea_random(-100, 100);
-
- info->satinfo.inuse = 0;
- info->satinfo.inview = 0;
-
- for(it = 0; it < 12; ++it)
- {
- info->satinfo.sat[it].id = it;
- info->satinfo.sat[it].in_use = in_use = (int)nmea_random(0, 3);
- info->satinfo.sat[it].elv = (int)nmea_random(0, 90);
- info->satinfo.sat[it].azimuth = (int)nmea_random(0, 359);
- info->satinfo.sat[it].sig = (int)(in_use?nmea_random(40, 99):nmea_random(0, 40));
-
- if(in_use)
- info->satinfo.inuse++;
- if(info->satinfo.sat[it].sig > 0)
- info->satinfo.inview++;
- }
-
- return 1;
-}
-
-int nmea_igen_noise_reset(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- return 1;
-}
-
-/*
- * STATIC generator
- */
-
-int nmea_igen_static_loop(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- nmea_time_now(&info->utc);
- return 1;
-};
-
-int nmea_igen_static_reset(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- info->satinfo.inuse = 4;
- info->satinfo.inview = 4;
-
- info->satinfo.sat[0].id = 1;
- info->satinfo.sat[0].in_use = 1;
- info->satinfo.sat[0].elv = 50;
- info->satinfo.sat[0].azimuth = 0;
- info->satinfo.sat[0].sig = 99;
-
- info->satinfo.sat[1].id = 2;
- info->satinfo.sat[1].in_use = 1;
- info->satinfo.sat[1].elv = 50;
- info->satinfo.sat[1].azimuth = 90;
- info->satinfo.sat[1].sig = 99;
-
- info->satinfo.sat[2].id = 3;
- info->satinfo.sat[2].in_use = 1;
- info->satinfo.sat[2].elv = 50;
- info->satinfo.sat[2].azimuth = 180;
- info->satinfo.sat[2].sig = 99;
-
- info->satinfo.sat[3].id = 4;
- info->satinfo.sat[3].in_use = 1;
- info->satinfo.sat[3].elv = 50;
- info->satinfo.sat[3].azimuth = 270;
- info->satinfo.sat[3].sig = 99;
-
- return 1;
-}
-
-int nmea_igen_static_init(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- info->sig = 3;
- info->fix = 3;
-
- nmea_igen_static_reset(gen, info);
-
- return 1;
-}
-
-/*
- * SAT_ROTATE generator
- */
-
-int nmea_igen_rotate_loop(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- int it;
- int count = info->satinfo.inview;
- float deg = 360 / (count?count:1);
- float srt = (count?(info->satinfo.sat[0].azimuth):0) + 5;
-
- nmea_time_now(&info->utc);
-
- for(it = 0; it < count; ++it)
- {
- info->satinfo.sat[it].azimuth =
- (int)((srt >= 360)?srt - 360:srt);
- srt += deg;
- }
-
- return 1;
-};
-
-int nmea_igen_rotate_reset(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- int it;
- float deg = 360 / 8;
- float srt = 0;
-
- info->satinfo.inuse = 8;
- info->satinfo.inview = 8;
-
- for(it = 0; it < info->satinfo.inview; ++it)
- {
- info->satinfo.sat[it].id = it + 1;
- info->satinfo.sat[it].in_use = 1;
- info->satinfo.sat[it].elv = 5;
- info->satinfo.sat[it].azimuth = (int)srt;
- info->satinfo.sat[it].sig = 80;
- srt += deg;
- }
-
- return 1;
-}
-
-int nmea_igen_rotate_init(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- info->sig = 3;
- info->fix = 3;
-
- nmea_igen_rotate_reset(gen, info);
-
- return 1;
-}
-
-/*
- * POS_RANDMOVE generator
- */
-
-int nmea_igen_pos_rmove_init(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- info->sig = 3;
- info->fix = 3;
- info->direction = info->declination = 0;
- info->speed = 20;
- return 1;
-}
-
-int nmea_igen_pos_rmove_loop(nmeaGENERATOR *gen, nmeaINFO *info)
-{
- nmeaPOS crd;
-
- info->direction += nmea_random(-10, 10);
- info->speed += nmea_random(-2, 3);
-
- if(info->direction < 0)
- info->direction = 359 + info->direction;
- if(info->direction > 359)
- info->direction -= 359;
-
- if(info->speed > 40)
- info->speed = 40;
- if(info->speed < 1)
- info->speed = 1;
-
- nmea_info2pos(info, &crd);
- nmea_move_horz(&crd, &crd, info->direction, info->speed / 3600);
- nmea_pos2info(&crd, info);
-
- info->declination = info->direction;
-
- return 1;
-};
-
-int nmea_igen_pos_rmove_destroy(nmeaGENERATOR *gen)
-{
- return 1;
-};
-
-/*
- * generator create
- */
-
-nmeaGENERATOR * __nmea_create_generator(int type, nmeaINFO *info)
-{
- nmeaGENERATOR *gen = 0;
-
- switch(type)
- {
- case NMEA_GEN_NOISE:
- if(0 == (gen = malloc(sizeof(nmeaGENERATOR))))
- nmea_error("Insufficient memory!");
- else
- {
- memset(gen, 0, sizeof(nmeaGENERATOR));
- gen->init_call = &nmea_igen_noise_init;
- gen->loop_call = &nmea_igen_noise_loop;
- gen->reset_call = &nmea_igen_noise_reset;
- }
- break;
- case NMEA_GEN_STATIC:
- case NMEA_GEN_SAT_STATIC:
- if(0 == (gen = malloc(sizeof(nmeaGENERATOR))))
- nmea_error("Insufficient memory!");
- else
- {
- memset(gen, 0, sizeof(nmeaGENERATOR));
- gen->init_call = &nmea_igen_static_init;
- gen->loop_call = &nmea_igen_static_loop;
- gen->reset_call = &nmea_igen_static_reset;
- }
- break;
- case NMEA_GEN_SAT_ROTATE:
- if(0 == (gen = malloc(sizeof(nmeaGENERATOR))))
- nmea_error("Insufficient memory!");
- else
- {
- memset(gen, 0, sizeof(nmeaGENERATOR));
- gen->init_call = &nmea_igen_rotate_init;
- gen->loop_call = &nmea_igen_rotate_loop;
- gen->reset_call = &nmea_igen_rotate_reset;
- }
- break;
- case NMEA_GEN_POS_RANDMOVE:
- if(0 == (gen = malloc(sizeof(nmeaGENERATOR))))
- nmea_error("Insufficient memory!");
- else
- {
- memset(gen, 0, sizeof(nmeaGENERATOR));
- gen->init_call = &nmea_igen_pos_rmove_init;
- gen->loop_call = &nmea_igen_pos_rmove_loop;
- gen->destroy_call = &nmea_igen_pos_rmove_destroy;
- }
- break;
- case NMEA_GEN_ROTATE:
- gen = __nmea_create_generator(NMEA_GEN_SAT_ROTATE, info);
- nmea_gen_add(gen, __nmea_create_generator(NMEA_GEN_POS_RANDMOVE, info));
- break;
- };
-
- return gen;
-}
-
-nmeaGENERATOR * nmea_create_generator(int type, nmeaINFO *info)
-{
- nmeaGENERATOR *gen = __nmea_create_generator(type, info);
-
- if(gen)
- nmea_gen_init(gen, info);
-
- return gen;
-}
-
-void nmea_destroy_generator(nmeaGENERATOR *gen)
-{
- nmea_gen_destroy(gen);
-}
-
-#if defined(NMEA_WIN) && defined(_MSC_VER)
-# pragma warning(default: 4100)
-#endif
diff --git a/apps/gps/nmealib/gmath.c b/apps/gps/nmealib/gmath.c
deleted file mode 100644
index 327b982ef..000000000
--- a/apps/gps/nmealib/gmath.c
+++ /dev/null
@@ -1,376 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: gmath.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-/*! \file gmath.h */
-#include "nmea/gmath.h"
-
-#include <math.h>
-#include <float.h>
-
-/**
- * \fn nmea_degree2radian
- * \brief Convert degree to radian
- */
-float nmea_degree2radian(float val)
-{ return (val * NMEA_PI180); }
-
-/**
- * \fn nmea_radian2degree
- * \brief Convert radian to degree
- */
-float nmea_radian2degree(float val)
-{ return (val / NMEA_PI180); }
-
-/**
- * \brief Convert NDEG (NMEA degree) to fractional degree
- */
-float nmea_ndeg2degree(float val)
-{
- float deg = ((int)(val / 100));
- val = deg + (val - deg * 100) / 60;
- return val;
-}
-
-/**
- * \brief Convert fractional degree to NDEG (NMEA degree)
- */
-float nmea_degree2ndeg(float val)
-{
- float int_part;
- float fra_part;
- fra_part = modf(val, &int_part);
- val = int_part * 100 + fra_part * 60;
- return val;
-}
-
-/**
- * \fn nmea_ndeg2radian
- * \brief Convert NDEG (NMEA degree) to radian
- */
-float nmea_ndeg2radian(float val)
-{ return nmea_degree2radian(nmea_ndeg2degree(val)); }
-
-/**
- * \fn nmea_radian2ndeg
- * \brief Convert radian to NDEG (NMEA degree)
- */
-float nmea_radian2ndeg(float val)
-{ return nmea_degree2ndeg(nmea_radian2degree(val)); }
-
-/**
- * \brief Calculate PDOP (Position Dilution Of Precision) factor
- */
-float nmea_calc_pdop(float hdop, float vdop)
-{
- return sqrt(pow(hdop, 2) + pow(vdop, 2));
-}
-
-float nmea_dop2meters(float dop)
-{ return (dop * NMEA_DOP_FACTOR); }
-
-float nmea_meters2dop(float meters)
-{ return (meters / NMEA_DOP_FACTOR); }
-
-/**
- * \brief Calculate distance between two points
- * \return Distance in meters
- */
-float nmea_distance(
- const nmeaPOS *from_pos, /**< From position in radians */
- const nmeaPOS *to_pos /**< To position in radians */
- )
-{
- float dist = ((float)NMEA_EARTHRADIUS_M) * acos(
- sin(to_pos->lat) * sin(from_pos->lat) +
- cos(to_pos->lat) * cos(from_pos->lat) * cos(to_pos->lon - from_pos->lon)
- );
- return dist;
-}
-
-/**
- * \brief Calculate distance between two points
- * This function uses an algorithm for an oblate spheroid earth model.
- * The algorithm is described here:
- * http://www.ngs.noaa.gov/PUBS_LIB/inverse.pdf
- * \return Distance in meters
- */
-float nmea_distance_ellipsoid(
- const nmeaPOS *from_pos, /**< From position in radians */
- const nmeaPOS *to_pos, /**< To position in radians */
- float *from_azimuth, /**< (O) azimuth at "from" position in radians */
- float *to_azimuth /**< (O) azimuth at "to" position in radians */
- )
-{
- /* All variables */
- float f, a, b, sqr_a, sqr_b;
- float L, phi1, phi2, U1, U2, sin_U1, sin_U2, cos_U1, cos_U2;
- float sigma, sin_sigma, cos_sigma, cos_2_sigmam, sqr_cos_2_sigmam, sqr_cos_alpha, lambda, sin_lambda, cos_lambda, delta_lambda;
- int remaining_steps;
- float sqr_u, A, B, delta_sigma;
-
- /* Check input */
- //NMEA_ASSERT(from_pos != 0);
- //NMEA_ASSERT(to_pos != 0);
-
- if ((from_pos->lat == to_pos->lat) && (from_pos->lon == to_pos->lon))
- { /* Identical points */
- if ( from_azimuth != 0 )
- *from_azimuth = 0;
- if ( to_azimuth != 0 )
- *to_azimuth = 0;
- return 0;
- } /* Identical points */
-
- /* Earth geometry */
- f = NMEA_EARTH_FLATTENING;
- a = NMEA_EARTH_SEMIMAJORAXIS_M;
- b = (1 - f) * a;
- sqr_a = a * a;
- sqr_b = b * b;
-
- /* Calculation */
- L = to_pos->lon - from_pos->lon;
- phi1 = from_pos->lat;
- phi2 = to_pos->lat;
- U1 = atan((1 - f) * tan(phi1));
- U2 = atan((1 - f) * tan(phi2));
- sin_U1 = sin(U1);
- sin_U2 = sin(U2);
- cos_U1 = cos(U1);
- cos_U2 = cos(U2);
-
- /* Initialize iteration */
- sigma = 0;
- sin_sigma = sin(sigma);
- cos_sigma = cos(sigma);
- cos_2_sigmam = 0;
- sqr_cos_2_sigmam = cos_2_sigmam * cos_2_sigmam;
- sqr_cos_alpha = 0;
- lambda = L;
- sin_lambda = sin(lambda);
- cos_lambda = cos(lambda);
- delta_lambda = lambda;
- remaining_steps = 20;
-
- while ((delta_lambda > 1e-12) && (remaining_steps > 0))
- { /* Iterate */
- /* Variables */
- float tmp1, tmp2, tan_sigma, sin_alpha, cos_alpha, C, lambda_prev;
-
- /* Calculation */
- tmp1 = cos_U2 * sin_lambda;
- tmp2 = cos_U1 * sin_U2 - sin_U1 * cos_U2 * cos_lambda;
- sin_sigma = sqrt(tmp1 * tmp1 + tmp2 * tmp2);
- cos_sigma = sin_U1 * sin_U2 + cos_U1 * cos_U2 * cos_lambda;
- tan_sigma = sin_sigma / cos_sigma;
- sin_alpha = cos_U1 * cos_U2 * sin_lambda / sin_sigma;
- cos_alpha = cos(asin(sin_alpha));
- sqr_cos_alpha = cos_alpha * cos_alpha;
- cos_2_sigmam = cos_sigma - 2 * sin_U1 * sin_U2 / sqr_cos_alpha;
- sqr_cos_2_sigmam = cos_2_sigmam * cos_2_sigmam;
- C = f / 16 * sqr_cos_alpha * (4 + f * (4 - 3 * sqr_cos_alpha));
- lambda_prev = lambda;
- sigma = asin(sin_sigma);
- lambda = L +
- (1 - C) * f * sin_alpha
- * (sigma + C * sin_sigma * (cos_2_sigmam + C * cos_sigma * (-1 + 2 * sqr_cos_2_sigmam)));
- delta_lambda = lambda_prev - lambda;
- if ( delta_lambda < 0 ) delta_lambda = -delta_lambda;
- sin_lambda = sin(lambda);
- cos_lambda = cos(lambda);
- remaining_steps--;
- } /* Iterate */
-
- /* More calculation */
- sqr_u = sqr_cos_alpha * (sqr_a - sqr_b) / sqr_b;
- A = 1 + sqr_u / 16384 * (4096 + sqr_u * (-768 + sqr_u * (320 - 175 * sqr_u)));
- B = sqr_u / 1024 * (256 + sqr_u * (-128 + sqr_u * (74 - 47 * sqr_u)));
- delta_sigma = B * sin_sigma * (
- cos_2_sigmam + B / 4 * (
- cos_sigma * (-1 + 2 * sqr_cos_2_sigmam) -
- B / 6 * cos_2_sigmam * (-3 + 4 * sin_sigma * sin_sigma) * (-3 + 4 * sqr_cos_2_sigmam)
- ));
-
- /* Calculate result */
- if ( from_azimuth != 0 )
- {
- float tan_alpha_1 = cos_U2 * sin_lambda / (cos_U1 * sin_U2 - sin_U1 * cos_U2 * cos_lambda);
- *from_azimuth = atan(tan_alpha_1);
- }
- if ( to_azimuth != 0 )
- {
- float tan_alpha_2 = cos_U1 * sin_lambda / (-sin_U1 * cos_U2 + cos_U1 * sin_U2 * cos_lambda);
- *to_azimuth = atan(tan_alpha_2);
- }
-
- return b * A * (sigma - delta_sigma);
-}
-
-/**
- * \brief Horizontal move of point position
- */
-int nmea_move_horz(
- const nmeaPOS *start_pos, /**< Start position in radians */
- nmeaPOS *end_pos, /**< Result position in radians */
- float azimuth, /**< Azimuth (degree) [0, 359] */
- float distance /**< Distance (km) */
- )
-{
- nmeaPOS p1 = *start_pos;
- int RetVal = 1;
-
- distance /= NMEA_EARTHRADIUS_KM; /* Angular distance covered on earth's surface */
- azimuth = nmea_degree2radian(azimuth);
-
- end_pos->lat = asin(
- sin(p1.lat) * cos(distance) + cos(p1.lat) * sin(distance) * cos(azimuth));
- end_pos->lon = p1.lon + atan2(
- sin(azimuth) * sin(distance) * cos(p1.lat), cos(distance) - sin(p1.lat) * sin(end_pos->lat));
-
- if(NMEA_POSIX(isnan)(end_pos->lat) || NMEA_POSIX(isnan)(end_pos->lon))
- {
- end_pos->lat = 0; end_pos->lon = 0;
- RetVal = 0;
- }
-
- return RetVal;
-}
-
-/**
- * \brief Horizontal move of point position
- * This function uses an algorithm for an oblate spheroid earth model.
- * The algorithm is described here:
- * http://www.ngs.noaa.gov/PUBS_LIB/inverse.pdf
- */
-int nmea_move_horz_ellipsoid(
- const nmeaPOS *start_pos, /**< Start position in radians */
- nmeaPOS *end_pos, /**< (O) Result position in radians */
- float azimuth, /**< Azimuth in radians */
- float distance, /**< Distance (km) */
- float *end_azimuth /**< (O) Azimuth at end position in radians */
- )
-{
- /* Variables */
- float f, a, b, sqr_a, sqr_b;
- float phi1, tan_U1, sin_U1, cos_U1, s, alpha1, sin_alpha1, cos_alpha1;
- float tan_sigma1, sigma1, sin_alpha, cos_alpha, sqr_cos_alpha, sqr_u, A, B;
- float sigma_initial, sigma, sigma_prev, sin_sigma, cos_sigma, cos_2_sigmam, sqr_cos_2_sigmam, delta_sigma;
- int remaining_steps;
- float tmp1, phi2, lambda, C, L;
-
- /* Check input */
- //NMEA_ASSERT(start_pos != 0);
- //NMEA_ASSERT(end_pos != 0);
-
- if (fabs(distance) < 1e-12)
- { /* No move */
- *end_pos = *start_pos;
- if ( end_azimuth != 0 ) *end_azimuth = azimuth;
- return ! (NMEA_POSIX(isnan)(end_pos->lat) || NMEA_POSIX(isnan)(end_pos->lon));
- } /* No move */
-
- /* Earth geometry */
- f = NMEA_EARTH_FLATTENING;
- a = NMEA_EARTH_SEMIMAJORAXIS_M;
- b = (1 - f) * a;
- sqr_a = a * a;
- sqr_b = b * b;
-
- /* Calculation */
- phi1 = start_pos->lat;
- tan_U1 = (1 - f) * tan(phi1);
- cos_U1 = 1 / sqrt(1 + tan_U1 * tan_U1);
- sin_U1 = tan_U1 * cos_U1;
- s = distance;
- alpha1 = azimuth;
- sin_alpha1 = sin(alpha1);
- cos_alpha1 = cos(alpha1);
- tan_sigma1 = tan_U1 / cos_alpha1;
- sigma1 = atan2(tan_U1, cos_alpha1);
- sin_alpha = cos_U1 * sin_alpha1;
- sqr_cos_alpha = 1 - sin_alpha * sin_alpha;
- cos_alpha = sqrt(sqr_cos_alpha);
- sqr_u = sqr_cos_alpha * (sqr_a - sqr_b) / sqr_b;
- A = 1 + sqr_u / 16384 * (4096 + sqr_u * (-768 + sqr_u * (320 - 175 * sqr_u)));
- B = sqr_u / 1024 * (256 + sqr_u * (-128 + sqr_u * (74 - 47 * sqr_u)));
-
- /* Initialize iteration */
- sigma_initial = s / (b * A);
- sigma = sigma_initial;
- sin_sigma = sin(sigma);
- cos_sigma = cos(sigma);
- cos_2_sigmam = cos(2 * sigma1 + sigma);
- sqr_cos_2_sigmam = cos_2_sigmam * cos_2_sigmam;
- delta_sigma = 0;
- sigma_prev = 2 * NMEA_PI;
- remaining_steps = 20;
-
- while ((fabs(sigma - sigma_prev) > 1e-12) && (remaining_steps > 0))
- { /* Iterate */
- cos_2_sigmam = cos(2 * sigma1 + sigma);
- sqr_cos_2_sigmam = cos_2_sigmam * cos_2_sigmam;
- sin_sigma = sin(sigma);
- cos_sigma = cos(sigma);
- delta_sigma = B * sin_sigma * (
- cos_2_sigmam + B / 4 * (
- cos_sigma * (-1 + 2 * sqr_cos_2_sigmam) -
- B / 6 * cos_2_sigmam * (-3 + 4 * sin_sigma * sin_sigma) * (-3 + 4 * sqr_cos_2_sigmam)
- ));
- sigma_prev = sigma;
- sigma = sigma_initial + delta_sigma;
- remaining_steps --;
- } /* Iterate */
-
- /* Calculate result */
- tmp1 = (sin_U1 * sin_sigma - cos_U1 * cos_sigma * cos_alpha1);
- phi2 = atan2(
- sin_U1 * cos_sigma + cos_U1 * sin_sigma * cos_alpha1,
- (1 - f) * sqrt(sin_alpha * sin_alpha + tmp1 * tmp1)
- );
- lambda = atan2(
- sin_sigma * sin_alpha1,
- cos_U1 * cos_sigma - sin_U1 * sin_sigma * cos_alpha1
- );
- C = f / 16 * sqr_cos_alpha * (4 + f * (4 - 3 * sqr_cos_alpha));
- L = lambda -
- (1 - C) * f * sin_alpha * (
- sigma + C * sin_sigma *
- (cos_2_sigmam + C * cos_sigma * (-1 + 2 * sqr_cos_2_sigmam))
- );
-
- /* Result */
- end_pos->lon = start_pos->lon + L;
- end_pos->lat = phi2;
- if ( end_azimuth != 0 )
- {
- *end_azimuth = atan2(
- sin_alpha, -sin_U1 * sin_sigma + cos_U1 * cos_sigma * cos_alpha1
- );
- }
- return ! (NMEA_POSIX(isnan)(end_pos->lat) || NMEA_POSIX(isnan)(end_pos->lon));
-}
-
-/**
- * \brief Convert position from INFO to radians position
- */
-void nmea_info2pos(const nmeaINFO *info, nmeaPOS *pos)
-{
- pos->lat = nmea_ndeg2radian(info->lat);
- pos->lon = nmea_ndeg2radian(info->lon);
-}
-
-/**
- * \brief Convert radians position to INFOs position
- */
-void nmea_pos2info(const nmeaPOS *pos, nmeaINFO *info)
-{
- info->lat = nmea_radian2ndeg(pos->lat);
- info->lon = nmea_radian2ndeg(pos->lon);
-}
diff --git a/apps/gps/nmealib/info.c b/apps/gps/nmealib/info.c
deleted file mode 100644
index 1d531ffc4..000000000
--- a/apps/gps/nmealib/info.c
+++ /dev/null
@@ -1,21 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: info.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#include <string.h>
-
-#include "nmea/info.h"
-
-void nmea_zero_INFO(nmeaINFO *info)
-{
- memset(info, 0, sizeof(nmeaINFO));
- nmea_time_now(&info->utc);
- info->sig = NMEA_SIG_BAD;
- info->fix = NMEA_FIX_BAD;
-}
diff --git a/apps/gps/nmealib/nmea/config.h b/apps/gps/nmealib/nmea/config.h
deleted file mode 100644
index 501466218..000000000
--- a/apps/gps/nmealib/nmea/config.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: config.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#ifndef __NMEA_CONFIG_H__
-#define __NMEA_CONFIG_H__
-
-#define NMEA_VERSION ("0.5.3")
-#define NMEA_VERSION_MAJOR (0)
-#define NMEA_VERSION_MINOR (5)
-#define NMEA_VERSION_PATCH (3)
-
-#define NMEA_CONVSTR_BUF (256)
-#define NMEA_TIMEPARSE_BUF (256)
-
-#if defined(WINCE) || defined(UNDER_CE)
-# define NMEA_CE
-#endif
-
-#if defined(WIN32) || defined(NMEA_CE)
-# define NMEA_WIN
-#else
-# define NMEA_UNI
-#endif
-
-#if defined(NMEA_WIN) && (_MSC_VER >= 1400)
-# pragma warning(disable: 4996) /* declared deprecated */
-#endif
-
-#if defined(_MSC_VER)
-# define NMEA_POSIX(x) _##x
-# define NMEA_INLINE __inline
-#else
-# define NMEA_POSIX(x) x
-# define NMEA_INLINE inline
-#endif
-
-#if !defined(NDEBUG) && !defined(NMEA_CE)
-# include <assert.h>
-# define NMEA_ASSERT(x) assert(x)
-#else
-# define NMEA_ASSERT(x)
-#endif
-
-#endif /* __NMEA_CONFIG_H__ */
diff --git a/apps/gps/nmealib/nmea/context.h b/apps/gps/nmealib/nmea/context.h
deleted file mode 100644
index 06e558327..000000000
--- a/apps/gps/nmealib/nmea/context.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: context.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_CONTEXT_H__
-#define __NMEA_CONTEXT_H__
-
-#include "config.h"
-
-#define NMEA_DEF_PARSEBUFF (1024)
-#define NMEA_MIN_PARSEBUFF (256)
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef void (*nmeaTraceFunc)(const char *str, int str_size);
-typedef void (*nmeaErrorFunc)(const char *str, int str_size);
-
-typedef struct _nmeaPROPERTY
-{
- nmeaTraceFunc trace_func;
- nmeaErrorFunc error_func;
- int parse_buff_size;
-
-} nmeaPROPERTY;
-
-nmeaPROPERTY * nmea_property(void);
-
-void nmea_trace(const char *str, ...);
-void nmea_trace_buff(const char *buff, int buff_size);
-void nmea_error(const char *str, ...);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_CONTEXT_H__ */
diff --git a/apps/gps/nmealib/nmea/generate.h b/apps/gps/nmealib/nmea/generate.h
deleted file mode 100644
index 9d7fdee51..000000000
--- a/apps/gps/nmealib/nmea/generate.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: generate.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_GENERATE_H__
-#define __NMEA_GENERATE_H__
-
-#include "sentence.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-int nmea_generate(
- char *buff, int buff_sz, /* buffer */
- const nmeaINFO *info, /* source info */
- int generate_mask /* mask of sentence`s (e.g. GPGGA | GPGSA) */
- );
-
-int nmea_gen_GPGGA(char *buff, int buff_sz, nmeaGPGGA *pack);
-int nmea_gen_GPGSA(char *buff, int buff_sz, nmeaGPGSA *pack);
-int nmea_gen_GPGSV(char *buff, int buff_sz, nmeaGPGSV *pack);
-int nmea_gen_GPRMC(char *buff, int buff_sz, nmeaGPRMC *pack);
-int nmea_gen_GPVTG(char *buff, int buff_sz, nmeaGPVTG *pack);
-
-void nmea_info2GPGGA(const nmeaINFO *info, nmeaGPGGA *pack);
-void nmea_info2GPGSA(const nmeaINFO *info, nmeaGPGSA *pack);
-void nmea_info2GPRMC(const nmeaINFO *info, nmeaGPRMC *pack);
-void nmea_info2GPVTG(const nmeaINFO *info, nmeaGPVTG *pack);
-
-int nmea_gsv_npack(int sat_count);
-void nmea_info2GPGSV(const nmeaINFO *info, nmeaGPGSV *pack, int pack_idx);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_GENERATE_H__ */
diff --git a/apps/gps/nmealib/nmea/generator.h b/apps/gps/nmealib/nmea/generator.h
deleted file mode 100644
index a97b91b13..000000000
--- a/apps/gps/nmealib/nmea/generator.h
+++ /dev/null
@@ -1,79 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: generator.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_GENERATOR_H__
-#define __NMEA_GENERATOR_H__
-
-#include "info.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- * high level
- */
-
-struct _nmeaGENERATOR;
-
-enum nmeaGENTYPE
-{
- NMEA_GEN_NOISE = 0,
- NMEA_GEN_STATIC,
- NMEA_GEN_ROTATE,
-
- NMEA_GEN_SAT_STATIC,
- NMEA_GEN_SAT_ROTATE,
- NMEA_GEN_POS_RANDMOVE,
-
- NMEA_GEN_LAST
-};
-
-struct _nmeaGENERATOR * nmea_create_generator(int type, nmeaINFO *info);
-void nmea_destroy_generator(struct _nmeaGENERATOR *gen);
-
-int nmea_generate_from(
- char *buff, int buff_sz, /* buffer */
- nmeaINFO *info, /* source info */
- struct _nmeaGENERATOR *gen, /* generator */
- int generate_mask /* mask of sentence`s (e.g. GPGGA | GPGSA) */
- );
-
-/*
- * low level
- */
-
-typedef int (*nmeaNMEA_GEN_INIT)(struct _nmeaGENERATOR *gen, nmeaINFO *info);
-typedef int (*nmeaNMEA_GEN_LOOP)(struct _nmeaGENERATOR *gen, nmeaINFO *info);
-typedef int (*nmeaNMEA_GEN_RESET)(struct _nmeaGENERATOR *gen, nmeaINFO *info);
-typedef int (*nmeaNMEA_GEN_DESTROY)(struct _nmeaGENERATOR *gen);
-
-typedef struct _nmeaGENERATOR
-{
- void *gen_data;
- nmeaNMEA_GEN_INIT init_call;
- nmeaNMEA_GEN_LOOP loop_call;
- nmeaNMEA_GEN_RESET reset_call;
- nmeaNMEA_GEN_DESTROY destroy_call;
- struct _nmeaGENERATOR *next;
-
-} nmeaGENERATOR;
-
-int nmea_gen_init(nmeaGENERATOR *gen, nmeaINFO *info);
-int nmea_gen_loop(nmeaGENERATOR *gen, nmeaINFO *info);
-int nmea_gen_reset(nmeaGENERATOR *gen, nmeaINFO *info);
-void nmea_gen_destroy(nmeaGENERATOR *gen);
-void nmea_gen_add(nmeaGENERATOR *to, nmeaGENERATOR *gen);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_GENERATOR_H__ */
diff --git a/apps/gps/nmealib/nmea/gmath.h b/apps/gps/nmealib/nmea/gmath.h
deleted file mode 100644
index 3133b7228..000000000
--- a/apps/gps/nmealib/nmea/gmath.h
+++ /dev/null
@@ -1,92 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: gmath.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#ifndef __NMEA_GMATH_H__
-#define __NMEA_GMATH_H__
-
-#include "info.h"
-
-#define NMEA_PI (3.141592653589793) /**< PI value */
-#define NMEA_PI180 (NMEA_PI / 180) /**< PI division by 180 */
-#define NMEA_EARTHRADIUS_KM (6378) /**< Earth's mean radius in km */
-#define NMEA_EARTHRADIUS_M (NMEA_EARTHRADIUS_KM * 1000) /**< Earth's mean radius in m */
-#define NMEA_EARTH_SEMIMAJORAXIS_M (6378137.0) /**< Earth's semi-major axis in m according WGS84 */
-#define NMEA_EARTH_SEMIMAJORAXIS_KM (NMEA_EARTHMAJORAXIS_KM / 1000) /**< Earth's semi-major axis in km according WGS 84 */
-#define NMEA_EARTH_FLATTENING (1 / 298.257223563) /**< Earth's flattening according WGS 84 */
-#define NMEA_DOP_FACTOR (5) /**< Factor for translating DOP to meters */
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- * degree VS radian
- */
-
-float nmea_degree2radian(float val);
-float nmea_radian2degree(float val);
-
-/*
- * NDEG (NMEA degree)
- */
-
-float nmea_ndeg2degree(float val);
-float nmea_degree2ndeg(float val);
-
-float nmea_ndeg2radian(float val);
-float nmea_radian2ndeg(float val);
-
-/*
- * DOP
- */
-
-float nmea_calc_pdop(float hdop, float vdop);
-float nmea_dop2meters(float dop);
-float nmea_meters2dop(float meters);
-
-/*
- * positions work
- */
-
-void nmea_info2pos(const nmeaINFO *info, nmeaPOS *pos);
-void nmea_pos2info(const nmeaPOS *pos, nmeaINFO *info);
-
-float nmea_distance(
- const nmeaPOS *from_pos,
- const nmeaPOS *to_pos
- );
-
-float nmea_distance_ellipsoid(
- const nmeaPOS *from_pos,
- const nmeaPOS *to_pos,
- float *from_azimuth,
- float *to_azimuth
- );
-
-int nmea_move_horz(
- const nmeaPOS *start_pos,
- nmeaPOS *end_pos,
- float azimuth,
- float distance
- );
-
-int nmea_move_horz_ellipsoid(
- const nmeaPOS *start_pos,
- nmeaPOS *end_pos,
- float azimuth,
- float distance,
- float *end_azimuth
- );
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_GMATH_H__ */
diff --git a/apps/gps/nmealib/nmea/info.h b/apps/gps/nmealib/nmea/info.h
deleted file mode 100644
index 09ccd4c09..000000000
--- a/apps/gps/nmealib/nmea/info.h
+++ /dev/null
@@ -1,112 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: info.h 10 2007-11-15 14:50:15Z xtimor $
- *
- */
-
-/*! \file */
-
-#ifndef __NMEA_INFO_H__
-#define __NMEA_INFO_H__
-
-#include "time.h"
-
-#define NMEA_SIG_BAD (0)
-#define NMEA_SIG_LOW (1)
-#define NMEA_SIG_MID (2)
-#define NMEA_SIG_HIGH (3)
-
-#define NMEA_FIX_BAD (1)
-#define NMEA_FIX_2D (2)
-#define NMEA_FIX_3D (3)
-
-#define NMEA_MAXSAT (12)
-#define NMEA_SATINPACK (4)
-#define NMEA_NSATPACKS (NMEA_MAXSAT / NMEA_SATINPACK)
-
-#define NMEA_DEF_LAT (5001.2621)
-#define NMEA_DEF_LON (3613.0595)
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/**
- * Position data in fractional degrees or radians
- */
-typedef struct _nmeaPOS
-{
- float lat; /**< Latitude */
- float lon; /**< Longitude */
-
-} nmeaPOS;
-
-/**
- * Information about satellite
- * @see nmeaSATINFO
- * @see nmeaGPGSV
- */
-typedef struct _nmeaSATELLITE
-{
- int id; /**< Satellite PRN number */
- int in_use; /**< Used in position fix */
- int elv; /**< Elevation in degrees, 90 maximum */
- int azimuth; /**< Azimuth, degrees from true north, 000 to 359 */
- int sig; /**< Signal, 00-99 dB */
-
-} nmeaSATELLITE;
-
-/**
- * Information about all satellites in view
- * @see nmeaINFO
- * @see nmeaGPGSV
- */
-typedef struct _nmeaSATINFO
-{
- int inuse; /**< Number of satellites in use (not those in view) */
- int inview; /**< Total number of satellites in view */
- nmeaSATELLITE sat[NMEA_MAXSAT]; /**< Satellites information */
-
-} nmeaSATINFO;
-
-/**
- * Summary GPS information from all parsed packets,
- * used also for generating NMEA stream
- * @see nmea_parse
- * @see nmea_GPGGA2info, nmea_...2info
- */
-typedef struct _nmeaINFO
-{
- int smask; /**< Mask specifying types of packages from which data have been obtained */
-
- nmeaTIME utc; /**< UTC of position */
-
- int sig; /**< GPS quality indicator (0 = Invalid; 1 = Fix; 2 = Differential, 3 = Sensitive) */
- int fix; /**< Operating mode, used for navigation (1 = Fix not available; 2 = 2D; 3 = 3D) */
-
- float PDOP; /**< Position Dilution Of Precision */
- float HDOP; /**< Horizontal Dilution Of Precision */
- float VDOP; /**< Vertical Dilution Of Precision */
-
- float lat; /**< Latitude in NDEG - +/-[degree][min].[sec/60] */
- float lon; /**< Longitude in NDEG - +/-[degree][min].[sec/60] */
- float elv; /**< Antenna altitude above/below mean sea level (geoid) in meters */
- float speed; /**< Speed over the ground in kilometers/hour */
- float direction; /**< Track angle in degrees True */
- float declination; /**< Magnetic variation degrees (Easterly var. subtracts from true course) */
-
- nmeaSATINFO satinfo; /**< Satellites information */
-
-} nmeaINFO;
-
-void nmea_zero_INFO(nmeaINFO *info);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_INFO_H__ */
diff --git a/apps/gps/nmealib/nmea/nmea.h b/apps/gps/nmealib/nmea/nmea.h
deleted file mode 100644
index 62692230f..000000000
--- a/apps/gps/nmealib/nmea/nmea.h
+++ /dev/null
@@ -1,25 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: nmea.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#ifndef __NMEA_H__
-#define __NMEA_H__
-
-#include "./config.h"
-#include "./units.h"
-#include "./gmath.h"
-#include "./info.h"
-#include "./sentence.h"
-#include "./generate.h"
-#include "./generator.h"
-#include "./parse.h"
-#include "./parser.h"
-#include "./context.h"
-
-#endif /* __NMEA_H__ */
diff --git a/apps/gps/nmealib/nmea/parse.h b/apps/gps/nmealib/nmea/parse.h
deleted file mode 100644
index 3e6b425db..000000000
--- a/apps/gps/nmealib/nmea/parse.h
+++ /dev/null
@@ -1,39 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: parse.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_PARSE_H__
-#define __NMEA_PARSE_H__
-
-#include "sentence.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-int nmea_pack_type(const char *buff, int buff_sz);
-int nmea_find_tail(const char *buff, int buff_sz, int *res_crc);
-
-int nmea_parse_GPGGA(const char *buff, int buff_sz, nmeaGPGGA *pack);
-int nmea_parse_GPGSA(const char *buff, int buff_sz, nmeaGPGSA *pack);
-int nmea_parse_GPGSV(const char *buff, int buff_sz, nmeaGPGSV *pack);
-int nmea_parse_GPRMC(const char *buff, int buff_sz, nmeaGPRMC *pack);
-int nmea_parse_GPVTG(const char *buff, int buff_sz, nmeaGPVTG *pack);
-
-void nmea_GPGGA2info(nmeaGPGGA *pack, nmeaINFO *info);
-void nmea_GPGSA2info(nmeaGPGSA *pack, nmeaINFO *info);
-void nmea_GPGSV2info(nmeaGPGSV *pack, nmeaINFO *info);
-void nmea_GPRMC2info(nmeaGPRMC *pack, nmeaINFO *info);
-void nmea_GPVTG2info(nmeaGPVTG *pack, nmeaINFO *info);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_PARSE_H__ */
diff --git a/apps/gps/nmealib/nmea/parser.h b/apps/gps/nmealib/nmea/parser.h
deleted file mode 100644
index 51a3fab7f..000000000
--- a/apps/gps/nmealib/nmea/parser.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: parser.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_PARSER_H__
-#define __NMEA_PARSER_H__
-
-#include "info.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- * high level
- */
-
-typedef struct _nmeaPARSER
-{
- void *top_node;
- void *end_node;
- unsigned char *buffer;
- int buff_size;
- int buff_use;
-
-} nmeaPARSER;
-
-int nmea_parser_init(nmeaPARSER *parser);
-void nmea_parser_destroy(nmeaPARSER *parser);
-
-int nmea_parse(
- nmeaPARSER *parser,
- const char *buff, int buff_sz,
- nmeaINFO *info
- );
-
-/*
- * low level
- */
-
-int nmea_parser_push(nmeaPARSER *parser, const char *buff, int buff_sz);
-int nmea_parser_top(nmeaPARSER *parser);
-int nmea_parser_pop(nmeaPARSER *parser, void **pack_ptr);
-int nmea_parser_peek(nmeaPARSER *parser, void **pack_ptr);
-int nmea_parser_drop(nmeaPARSER *parser);
-int nmea_parser_buff_clear(nmeaPARSER *parser);
-int nmea_parser_queue_clear(nmeaPARSER *parser);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_PARSER_H__ */
diff --git a/apps/gps/nmealib/nmea/sentence.h b/apps/gps/nmealib/nmea/sentence.h
deleted file mode 100644
index 2aa975c71..000000000
--- a/apps/gps/nmealib/nmea/sentence.h
+++ /dev/null
@@ -1,128 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: sentence.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-/*! \file */
-
-#ifndef __NMEA_SENTENCE_H__
-#define __NMEA_SENTENCE_H__
-
-#include "info.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/**
- * NMEA packets type which parsed and generated by library
- */
-enum nmeaPACKTYPE
-{
- GPNON = 0x0000, /**< Unknown packet type. */
- GPGGA = 0x0001, /**< GGA - Essential fix data which provide 3D location and accuracy data. */
- GPGSA = 0x0002, /**< GSA - GPS receiver operating mode, SVs used for navigation, and DOP values. */
- GPGSV = 0x0004, /**< GSV - Number of SVs in view, PRN numbers, elevation, azimuth & SNR values. */
- GPRMC = 0x0008, /**< RMC - Recommended Minimum Specific GPS/TRANSIT Data. */
- GPVTG = 0x0010 /**< VTG - Actual track made good and speed over ground. */
-};
-
-/**
- * GGA packet information structure (Global Positioning System Fix Data)
- */
-typedef struct _nmeaGPGGA
-{
- nmeaTIME utc; /**< UTC of position (just time) */
- float lat; /**< Latitude in NDEG - [degree][min].[sec/60] */
- char ns; /**< [N]orth or [S]outh */
- float lon; /**< Longitude in NDEG - [degree][min].[sec/60] */
- char ew; /**< [E]ast or [W]est */
- int sig; /**< GPS quality indicator (0 = Invalid; 1 = Fix; 2 = Differential, 3 = Sensitive) */
- int satinuse; /**< Number of satellites in use (not those in view) */
- float HDOP; /**< Horizontal dilution of precision */
- float elv; /**< Antenna altitude above/below mean sea level (geoid) */
- char elv_units; /**< [M]eters (Antenna height unit) */
- float diff; /**< Geoidal separation (Diff. between WGS-84 earth ellipsoid and mean sea level. '-' = geoid is below WGS-84 ellipsoid) */
- char diff_units; /**< [M]eters (Units of geoidal separation) */
- float dgps_age; /**< Time in seconds since last DGPS update */
- int dgps_sid; /**< DGPS station ID number */
-
-} nmeaGPGGA;
-
-/**
- * GSA packet information structure (Satellite status)
- */
-typedef struct _nmeaGPGSA
-{
- char fix_mode; /**< Mode (M = Manual, forced to operate in 2D or 3D; A = Automatic, 3D/2D) */
- int fix_type; /**< Type, used for navigation (1 = Fix not available; 2 = 2D; 3 = 3D) */
- int sat_prn[NMEA_MAXSAT]; /**< PRNs of satellites used in position fix (null for unused fields) */
- float PDOP; /**< Dilution of precision */
- float HDOP; /**< Horizontal dilution of precision */
- float VDOP; /**< Vertical dilution of precision */
-
-} nmeaGPGSA;
-
-/**
- * GSV packet information structure (Satellites in view)
- */
-typedef struct _nmeaGPGSV
-{
- int pack_count; /**< Total number of messages of this type in this cycle */
- int pack_index; /**< Message number */
- int sat_count; /**< Total number of satellites in view */
- nmeaSATELLITE sat_data[NMEA_SATINPACK];
-
-} nmeaGPGSV;
-
-/**
- * RMC packet information structure (Recommended Minimum sentence C)
- */
-typedef struct _nmeaGPRMC
-{
- nmeaTIME utc; /**< UTC of position */
- char status; /**< Status (A = active or V = void) */
- float lat; /**< Latitude in NDEG - [degree][min].[sec/60] */
- char ns; /**< [N]orth or [S]outh */
- float lon; /**< Longitude in NDEG - [degree][min].[sec/60] */
- char ew; /**< [E]ast or [W]est */
- float speed; /**< Speed over the ground in knots */
- float direction; /**< Track angle in degrees True */
- float declination; /**< Magnetic variation degrees (Easterly var. subtracts from true course) */
- char declin_ew; /**< [E]ast or [W]est */
- char mode; /**< Mode indicator of fix type (A = autonomous, D = differential, E = estimated, N = not valid, S = simulator) */
-
-} nmeaGPRMC;
-
-/**
- * VTG packet information structure (Track made good and ground speed)
- */
-typedef struct _nmeaGPVTG
-{
- float dir; /**< True track made good (degrees) */
- char dir_t; /**< Fixed text 'T' indicates that track made good is relative to true north */
- float dec; /**< Magnetic track made good */
- char dec_m; /**< Fixed text 'M' */
- float spn; /**< Ground speed, knots */
- char spn_n; /**< Fixed text 'N' indicates that speed over ground is in knots */
- float spk; /**< Ground speed, kilometers per hour */
- char spk_k; /**< Fixed text 'K' indicates that speed over ground is in kilometers/hour */
-
-} nmeaGPVTG;
-
-void nmea_zero_GPGGA(nmeaGPGGA *pack);
-void nmea_zero_GPGSA(nmeaGPGSA *pack);
-void nmea_zero_GPGSV(nmeaGPGSV *pack);
-void nmea_zero_GPRMC(nmeaGPRMC *pack);
-void nmea_zero_GPVTG(nmeaGPVTG *pack);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_SENTENCE_H__ */
diff --git a/apps/gps/nmealib/nmea/time.h b/apps/gps/nmealib/nmea/time.h
deleted file mode 100644
index bbe59f65c..000000000
--- a/apps/gps/nmealib/nmea/time.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: time.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-/*! \file */
-
-#ifndef __NMEA_TIME_H__
-#define __NMEA_TIME_H__
-
-#include "config.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/**
- * Date and time data
- * @see nmea_time_now
- */
-typedef struct _nmeaTIME
-{
- int year; /**< Years since 1900 */
- int mon; /**< Months since January - [0,11] */
- int day; /**< Day of the month - [1,31] */
- int hour; /**< Hours since midnight - [0,23] */
- int min; /**< Minutes after the hour - [0,59] */
- int sec; /**< Seconds after the minute - [0,59] */
- int hsec; /**< Hundredth part of second - [0,99] */
-
-} nmeaTIME;
-
-/**
- * \brief Get time now to nmeaTIME structure
- */
-void nmea_time_now(nmeaTIME *t);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_TIME_H__ */
diff --git a/apps/gps/nmealib/nmea/tok.h b/apps/gps/nmealib/nmea/tok.h
deleted file mode 100644
index 8f948dd2d..000000000
--- a/apps/gps/nmealib/nmea/tok.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: tok.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_TOK_H__
-#define __NMEA_TOK_H__
-
-#include "config.h"
-#include <string.h>
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-int nmea_calc_crc(const char *buff, int buff_sz);
-int nmea_atoi(const char *str, int str_sz, int radix);
-float nmea_atof(const char *str, int str_sz);
-int nmea_printf(char *buff, int buff_sz, const char *format, ...);
-int nmea_scanf(const char *buff, int buff_sz, const char *format, ...);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_TOK_H__ */
diff --git a/apps/gps/nmealib/nmea/units.h b/apps/gps/nmealib/nmea/units.h
deleted file mode 100644
index 767f980e2..000000000
--- a/apps/gps/nmealib/nmea/units.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: units.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_UNITS_H__
-#define __NMEA_UNITS_H__
-
-#include "config.h"
-
-/*
- * Distance units
- */
-
-#define NMEA_TUD_YARDS (1.0936) /**< Yeards, meter * NMEA_TUD_YARDS = yard */
-#define NMEA_TUD_KNOTS (1.852) /**< Knots, kilometer / NMEA_TUD_KNOTS = knot */
-#define NMEA_TUD_MILES (1.609) /**< Miles, kilometer / NMEA_TUD_MILES = mile */
-
-/*
- * Speed units
- */
-
-#define NMEA_TUS_MS (3.6) /**< Meters per seconds, (k/h) / NMEA_TUS_MS= (m/s) */
-
-#endif /* __NMEA_UNITS_H__ */
diff --git a/apps/gps/nmealib/parse.c b/apps/gps/nmealib/parse.c
deleted file mode 100644
index 99bdf075b..000000000
--- a/apps/gps/nmealib/parse.c
+++ /dev/null
@@ -1,501 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: parse.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-/**
- * \file parse.h
- * \brief Functions of a low level for analysis of
- * packages of NMEA stream.
- *
- * \code
- * ...
- * ptype = nmea_pack_type(
- * (const char *)parser->buffer + nparsed + 1,
- * parser->buff_use - nparsed - 1);
- *
- * if(0 == (node = malloc(sizeof(nmeaParserNODE))))
- * goto mem_fail;
- *
- * node->pack = 0;
- *
- * switch(ptype)
- * {
- * case GPGGA:
- * if(0 == (node->pack = malloc(sizeof(nmeaGPGGA))))
- * goto mem_fail;
- * node->packType = GPGGA;
- * if(!nmea_parse_GPGGA(
- * (const char *)parser->buffer + nparsed,
- * sen_sz, (nmeaGPGGA *)node->pack))
- * {
- * free(node);
- * node = 0;
- * }
- * break;
- * case GPGSA:
- * if(0 == (node->pack = malloc(sizeof(nmeaGPGSA))))
- * goto mem_fail;
- * node->packType = GPGSA;
- * if(!nmea_parse_GPGSA(
- * (const char *)parser->buffer + nparsed,
- * sen_sz, (nmeaGPGSA *)node->pack))
- * {
- * free(node);
- * node = 0;
- * }
- * break;
- * ...
- * \endcode
- */
-#include "nmea/tok.h"
-#include "nmea/parse.h"
-#include "nmea/context.h"
-#include "nmea/gmath.h"
-#include "nmea/units.h"
-
-#include <string.h>
-#include <stdio.h>
-
-int _nmea_parse_time(const char *buff, int buff_sz, nmeaTIME *res)
-{
- int success = 0;
-
- switch(buff_sz)
- {
- case sizeof("hhmmss") - 1:
- success = (3 == nmea_scanf(buff, buff_sz,
- "%2d%2d%2d", &(res->hour), &(res->min), &(res->sec)
- ));
- break;
- case sizeof("hhmmss.s") - 1:
- case sizeof("hhmmss.ss") - 1:
- case sizeof("hhmmss.sss") - 1:
- success = (4 == nmea_scanf(buff, buff_sz,
- "%2d%2d%2d.%d", &(res->hour), &(res->min), &(res->sec), &(res->hsec)
- ));
- break;
- default:
- nmea_error("Parse of time error (format error)!");
- success = 0;
- break;
- }
-
- return (success?0:-1);
-}
-
-/**
- * \brief Define packet type by header (nmeaPACKTYPE).
- * @param buff a constant character pointer of packet buffer.
- * @param buff_sz buffer size.
- * @return The defined packet type
- * @see nmeaPACKTYPE
- */
-int nmea_pack_type(const char *buff, int buff_sz)
-{
- static const char *pheads[] = {
- "GPGGA",
- "GPGSA",
- "GPGSV",
- "GPRMC",
- "GPVTG",
- };
-
- //NMEA_ASSERT(buff);
-
- if(buff_sz < 5)
- return GPNON;
- else if(0 == memcmp(buff, pheads[0], 5))
- return GPGGA;
- else if(0 == memcmp(buff, pheads[1], 5))
- return GPGSA;
- else if(0 == memcmp(buff, pheads[2], 5))
- return GPGSV;
- else if(0 == memcmp(buff, pheads[3], 5))
- return GPRMC;
- else if(0 == memcmp(buff, pheads[4], 5))
- return GPVTG;
-
- return GPNON;
-}
-
-/**
- * \brief Find tail of packet ("\r\n") in buffer and check control sum (CRC).
- * @param buff a constant character pointer of packets buffer.
- * @param buff_sz buffer size.
- * @param res_crc a integer pointer for return CRC of packet (must be defined).
- * @return Number of bytes to packet tail.
- */
-int nmea_find_tail(const char *buff, int buff_sz, int *res_crc)
-{
- static const int tail_sz = 3 /* *[CRC] */ + 2 /* \r\n */;
-
- const char *end_buff = buff + buff_sz;
- int nread = 0;
- int crc = 0;
-
- //NMEA_ASSERT(buff && res_crc);
-
- *res_crc = -1;
-
- for(;buff < end_buff; ++buff, ++nread)
- {
- if(('$' == *buff) && nread)
- {
- buff = 0;
- break;
- }
- else if('*' == *buff)
- {
- if(buff + tail_sz <= end_buff && '\r' == buff[3] && '\n' == buff[4])
- {
- *res_crc = nmea_atoi(buff + 1, 2, 16);
- nread = buff_sz - (int)(end_buff - (buff + tail_sz));
- if(*res_crc != crc)
- {
- *res_crc = -1;
- buff = 0;
- }
- }
-
- break;
- }
- else if(nread)
- crc ^= (int)*buff;
- }
-
- if(*res_crc < 0 && buff)
- nread = 0;
-
- return nread;
-}
-
-/**
- * \brief Parse GGA packet from buffer.
- * @param buff a constant character pointer of packet buffer.
- * @param buff_sz buffer size.
- * @param pack a pointer of packet which will filled by function.
- * @return 1 (true) - if parsed successfully or 0 (false) - if fail.
- */
-int nmea_parse_GPGGA(const char *buff, int buff_sz, nmeaGPGGA *pack)
-{
- char time_buff[NMEA_TIMEPARSE_BUF];
-
- //NMEA_ASSERT(buff && pack);
-
- memset(pack, 0, sizeof(nmeaGPGGA));
-
- nmea_trace_buff(buff, buff_sz);
-
- if(14 != nmea_scanf(buff, buff_sz,
- "$GPGGA,%s,%f,%C,%f,%C,%d,%d,%f,%f,%C,%f,%C,%f,%d*",
- &(time_buff[0]),
- &(pack->lat), &(pack->ns), &(pack->lon), &(pack->ew),
- &(pack->sig), &(pack->satinuse), &(pack->HDOP), &(pack->elv), &(pack->elv_units),
- &(pack->diff), &(pack->diff_units), &(pack->dgps_age), &(pack->dgps_sid)))
- {
- nmea_error("GPGGA parse error!");
- return 0;
- }
-
- if(0 != _nmea_parse_time(&time_buff[0], (int)strlen(&time_buff[0]), &(pack->utc)))
- {
- nmea_error("GPGGA time parse error!");
- return 0;
- }
-
- return 1;
-}
-
-/**
- * \brief Parse GSA packet from buffer.
- * @param buff a constant character pointer of packet buffer.
- * @param buff_sz buffer size.
- * @param pack a pointer of packet which will filled by function.
- * @return 1 (true) - if parsed successfully or 0 (false) - if fail.
- */
-int nmea_parse_GPGSA(const char *buff, int buff_sz, nmeaGPGSA *pack)
-{
- //NMEA_ASSERT(buff && pack);
-
- memset(pack, 0, sizeof(nmeaGPGSA));
-
- nmea_trace_buff(buff, buff_sz);
-
- if(17 != nmea_scanf(buff, buff_sz,
- "$GPGSA,%C,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%f,%f,%f*",
- &(pack->fix_mode), &(pack->fix_type),
- &(pack->sat_prn[0]), &(pack->sat_prn[1]), &(pack->sat_prn[2]), &(pack->sat_prn[3]), &(pack->sat_prn[4]), &(pack->sat_prn[5]),
- &(pack->sat_prn[6]), &(pack->sat_prn[7]), &(pack->sat_prn[8]), &(pack->sat_prn[9]), &(pack->sat_prn[10]), &(pack->sat_prn[11]),
- &(pack->PDOP), &(pack->HDOP), &(pack->VDOP)))
- {
- nmea_error("GPGSA parse error!");
- return 0;
- }
-
- return 1;
-}
-
-/**
- * \brief Parse GSV packet from buffer.
- * @param buff a constant character pointer of packet buffer.
- * @param buff_sz buffer size.
- * @param pack a pointer of packet which will filled by function.
- * @return 1 (true) - if parsed successfully or 0 (false) - if fail.
- */
-int nmea_parse_GPGSV(const char *buff, int buff_sz, nmeaGPGSV *pack)
-{
- int nsen, nsat;
-
- //NMEA_ASSERT(buff && pack);
-
- memset(pack, 0, sizeof(nmeaGPGSV));
-
- nmea_trace_buff(buff, buff_sz);
-
- nsen = nmea_scanf(buff, buff_sz,
- "$GPGSV,%d,%d,%d,"
- "%d,%d,%d,%d,"
- "%d,%d,%d,%d,"
- "%d,%d,%d,%d,"
- "%d,%d,%d,%d*",
- &(pack->pack_count), &(pack->pack_index), &(pack->sat_count),
- &(pack->sat_data[0].id), &(pack->sat_data[0].elv), &(pack->sat_data[0].azimuth), &(pack->sat_data[0].sig),
- &(pack->sat_data[1].id), &(pack->sat_data[1].elv), &(pack->sat_data[1].azimuth), &(pack->sat_data[1].sig),
- &(pack->sat_data[2].id), &(pack->sat_data[2].elv), &(pack->sat_data[2].azimuth), &(pack->sat_data[2].sig),
- &(pack->sat_data[3].id), &(pack->sat_data[3].elv), &(pack->sat_data[3].azimuth), &(pack->sat_data[3].sig));
-
- nsat = (pack->pack_index - 1) * NMEA_SATINPACK;
- nsat = (nsat + NMEA_SATINPACK > pack->sat_count)?pack->sat_count - nsat:NMEA_SATINPACK;
- nsat = nsat * 4 + 3 /* first three sentence`s */;
-
- if(nsen < nsat || nsen > (NMEA_SATINPACK * 4 + 3))
- {
- nmea_error("GPGSV parse error!");
- return 0;
- }
-
- return 1;
-}
-
-/**
- * \brief Parse RMC packet from buffer.
- * @param buff a constant character pointer of packet buffer.
- * @param buff_sz buffer size.
- * @param pack a pointer of packet which will filled by function.
- * @return 1 (true) - if parsed successfully or 0 (false) - if fail.
- */
-int nmea_parse_GPRMC(const char *buff, int buff_sz, nmeaGPRMC *pack)
-{
- int nsen;
- char time_buff[NMEA_TIMEPARSE_BUF];
-
- //NMEA_ASSERT(buff && pack);
-
- memset(pack, 0, sizeof(nmeaGPRMC));
-
- nmea_trace_buff(buff, buff_sz);
-
- nsen = nmea_scanf(buff, buff_sz,
- "$GPRMC,%s,%C,%f,%C,%f,%C,%f,%f,%2d%2d%2d,%f,%C,%C*",
- &(time_buff[0]),
- &(pack->status), &(pack->lat), &(pack->ns), &(pack->lon), &(pack->ew),
- &(pack->speed), &(pack->direction),
- &(pack->utc.day), &(pack->utc.mon), &(pack->utc.year),
- &(pack->declination), &(pack->declin_ew), &(pack->mode));
-
- if(nsen != 13 && nsen != 14)
- {
- nmea_error("GPRMC parse error!");
- return 0;
- }
-
- if(0 != _nmea_parse_time(&time_buff[0], (int)strlen(&time_buff[0]), &(pack->utc)))
- {
- nmea_error("GPRMC time parse error!");
- return 0;
- }
-
- if(pack->utc.year < 90)
- pack->utc.year += 100;
- pack->utc.mon -= 1;
-
- return 1;
-}
-
-/**
- * \brief Parse VTG packet from buffer.
- * @param buff a constant character pointer of packet buffer.
- * @param buff_sz buffer size.
- * @param pack a pointer of packet which will filled by function.
- * @return 1 (true) - if parsed successfully or 0 (false) - if fail.
- */
-int nmea_parse_GPVTG(const char *buff, int buff_sz, nmeaGPVTG *pack)
-{
- //NMEA_ASSERT(buff && pack);
-
- memset(pack, 0, sizeof(nmeaGPVTG));
-
- nmea_trace_buff(buff, buff_sz);
-
- if(8 != nmea_scanf(buff, buff_sz,
- "$GPVTG,%f,%C,%f,%C,%f,%C,%f,%C*",
- &(pack->dir), &(pack->dir_t),
- &(pack->dec), &(pack->dec_m),
- &(pack->spn), &(pack->spn_n),
- &(pack->spk), &(pack->spk_k)))
- {
- nmea_error("GPVTG parse error!");
- return 0;
- }
-
- if( pack->dir_t != 'T' ||
- pack->dec_m != 'M' ||
- pack->spn_n != 'N' ||
- pack->spk_k != 'K')
- {
- nmea_error("GPVTG parse error (format error)!");
- return 0;
- }
-
- return 1;
-}
-
-/**
- * \brief Fill nmeaINFO structure by GGA packet data.
- * @param pack a pointer of packet structure.
- * @param info a pointer of summary information structure.
- */
-void nmea_GPGGA2info(nmeaGPGGA *pack, nmeaINFO *info)
-{
- //NMEA_ASSERT(pack && info);
-
- info->utc.hour = pack->utc.hour;
- info->utc.min = pack->utc.min;
- info->utc.sec = pack->utc.sec;
- info->utc.hsec = pack->utc.hsec;
- info->sig = pack->sig;
- info->HDOP = pack->HDOP;
- info->elv = pack->elv;
- info->lat = ((pack->ns == 'N')?pack->lat:-(pack->lat));
- info->lon = ((pack->ew == 'E')?pack->lon:-(pack->lon));
- info->smask |= GPGGA;
-}
-
-/**
- * \brief Fill nmeaINFO structure by GSA packet data.
- * @param pack a pointer of packet structure.
- * @param info a pointer of summary information structure.
- */
-void nmea_GPGSA2info(nmeaGPGSA *pack, nmeaINFO *info)
-{
- int i, j, nuse = 0;
-
- //NMEA_ASSERT(pack && info);
-
- info->fix = pack->fix_type;
- info->PDOP = pack->PDOP;
- info->HDOP = pack->HDOP;
- info->VDOP = pack->VDOP;
-
- for(i = 0; i < NMEA_MAXSAT; ++i)
- {
- for(j = 0; j < info->satinfo.inview; ++j)
- {
- if(pack->sat_prn[i] && pack->sat_prn[i] == info->satinfo.sat[j].id)
- {
- info->satinfo.sat[j].in_use = 1;
- nuse++;
- }
- }
- }
-
- info->satinfo.inuse = nuse;
- info->smask |= GPGSA;
-}
-
-/**
- * \brief Fill nmeaINFO structure by GSV packet data.
- * @param pack a pointer of packet structure.
- * @param info a pointer of summary information structure.
- */
-void nmea_GPGSV2info(nmeaGPGSV *pack, nmeaINFO *info)
-{
- int isat, isi, nsat;
-
- //NMEA_ASSERT(pack && info);
-
- if(pack->pack_index > pack->pack_count ||
- pack->pack_index * NMEA_SATINPACK > NMEA_MAXSAT)
- return;
-
- if(pack->pack_index < 1)
- pack->pack_index = 1;
-
- info->satinfo.inview = pack->sat_count;
-
- nsat = (pack->pack_index - 1) * NMEA_SATINPACK;
- nsat = (nsat + NMEA_SATINPACK > pack->sat_count)?pack->sat_count - nsat:NMEA_SATINPACK;
-
- for(isat = 0; isat < nsat; ++isat)
- {
- isi = (pack->pack_index - 1) * NMEA_SATINPACK + isat;
- info->satinfo.sat[isi].id = pack->sat_data[isat].id;
- info->satinfo.sat[isi].elv = pack->sat_data[isat].elv;
- info->satinfo.sat[isi].azimuth = pack->sat_data[isat].azimuth;
- info->satinfo.sat[isi].sig = pack->sat_data[isat].sig;
- }
-
- info->smask |= GPGSV;
-}
-
-/**
- * \brief Fill nmeaINFO structure by RMC packet data.
- * @param pack a pointer of packet structure.
- * @param info a pointer of summary information structure.
- */
-void nmea_GPRMC2info(nmeaGPRMC *pack, nmeaINFO *info)
-{
- //NMEA_ASSERT(pack && info);
-
- if('A' == pack->status)
- {
- if(NMEA_SIG_BAD == info->sig)
- info->sig = NMEA_SIG_MID;
- if(NMEA_FIX_BAD == info->fix)
- info->fix = NMEA_FIX_2D;
- }
- else if('V' == pack->status)
- {
- info->sig = NMEA_SIG_BAD;
- info->fix = NMEA_FIX_BAD;
- }
-
-
- info->utc = pack->utc;
- info->lat = ((pack->ns == 'N')?pack->lat:-(pack->lat));
- info->lon = ((pack->ew == 'E')?pack->lon:-(pack->lon));
- info->speed = pack->speed * NMEA_TUD_KNOTS;
- info->direction = pack->direction;
- info->smask |= GPRMC;
-}
-
-/**
- * \brief Fill nmeaINFO structure by VTG packet data.
- * @param pack a pointer of packet structure.
- * @param info a pointer of summary information structure.
- */
-void nmea_GPVTG2info(nmeaGPVTG *pack, nmeaINFO *info)
-{
- //NMEA_ASSERT(pack && info);
-
- info->direction = pack->dir;
- info->declination = pack->dec;
- info->speed = pack->spk;
- info->smask |= GPVTG;
-}
diff --git a/apps/gps/nmealib/parser.c b/apps/gps/nmealib/parser.c
deleted file mode 100644
index f8b415866..000000000
--- a/apps/gps/nmealib/parser.c
+++ /dev/null
@@ -1,400 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: parser.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-/**
- * \file parser.h
- */
-#include "nmea/tok.h"
-#include "nmea/parse.h"
-#include "nmea/parser.h"
-#include "nmea/context.h"
-
-#include <string.h>
-#include <stdlib.h>
-
-typedef struct _nmeaParserNODE
-{
- int packType;
- void *pack;
- struct _nmeaParserNODE *next_node;
-
-} nmeaParserNODE;
-
-/*
- * high level
- */
-
-/**
- * \brief Initialization of parser object
- * @return true (1) - success or false (0) - fail
- */
-int nmea_parser_init(nmeaPARSER *parser)
-{
- int resv = 0;
- int buff_size = nmea_property()->parse_buff_size;
-
- //NMEA_ASSERT(parser);
-
- if(buff_size < NMEA_MIN_PARSEBUFF)
- buff_size = NMEA_MIN_PARSEBUFF;
-
- memset(parser, 0, sizeof(nmeaPARSER));
-
- if(0 == (parser->buffer = malloc(buff_size)))
- nmea_error("Insufficient memory!");
- else
- {
- parser->buff_size = buff_size;
- resv = 1;
- }
-
- return resv;
-}
-
-/**
- * \brief Destroy parser object
- */
-void nmea_parser_destroy(nmeaPARSER *parser)
-{
- //NMEA_ASSERT(parser && parser->buffer);
- free(parser->buffer);
- nmea_parser_queue_clear(parser);
- memset(parser, 0, sizeof(nmeaPARSER));
-}
-
-/**
- * \brief Analysis of buffer and put results to information structure
- * @return Number of packets wos parsed
- */
-int nmea_parse(
- nmeaPARSER *parser,
- const char *buff, int buff_sz,
- nmeaINFO *info
- )
-{
- int ptype, nread = 0;
- void *pack = 0;
-
- //NMEA_ASSERT(parser && parser->buffer);
-
- nmea_parser_push(parser, buff, buff_sz);
-
- while(GPNON != (ptype = nmea_parser_pop(parser, &pack)))
- {
- nread++;
-
- switch(ptype)
- {
- case GPGGA:
- nmea_GPGGA2info((nmeaGPGGA *)pack, info);
- break;
- case GPGSA:
- nmea_GPGSA2info((nmeaGPGSA *)pack, info);
- break;
- case GPGSV:
- nmea_GPGSV2info((nmeaGPGSV *)pack, info);
- break;
- case GPRMC:
- nmea_GPRMC2info((nmeaGPRMC *)pack, info);
- break;
- case GPVTG:
- nmea_GPVTG2info((nmeaGPVTG *)pack, info);
- break;
- };
-
- free(pack);
- }
-
- return nread;
-}
-
-/*
- * low level
- */
-
-int nmea_parser_real_push(nmeaPARSER *parser, const char *buff, int buff_sz)
-{
- int nparsed = 0, crc, sen_sz, ptype;
- nmeaParserNODE *node = 0;
-
- //NMEA_ASSERT(parser && parser->buffer);
-
- /* clear unuse buffer (for debug) */
- /*
- memset(
- parser->buffer + parser->buff_use, 0,
- parser->buff_size - parser->buff_use
- );
- */
-
- /* add */
- if(parser->buff_use + buff_sz >= parser->buff_size)
- nmea_parser_buff_clear(parser);
-
- memcpy(parser->buffer + parser->buff_use, buff, buff_sz);
- parser->buff_use += buff_sz;
-
- /* parse */
- for(;;node = 0)
- {
- sen_sz = nmea_find_tail(
- (const char *)parser->buffer + nparsed,
- (int)parser->buff_use - nparsed, &crc);
-
- if(!sen_sz)
- {
- if(nparsed)
- memcpy(
- parser->buffer,
- parser->buffer + nparsed,
- parser->buff_use -= nparsed);
- break;
- }
- else if(crc >= 0)
- {
- ptype = nmea_pack_type(
- (const char *)parser->buffer + nparsed + 1,
- parser->buff_use - nparsed - 1);
-
- if(0 == (node = malloc(sizeof(nmeaParserNODE))))
- goto mem_fail;
-
- node->pack = 0;
-
- switch(ptype)
- {
- case GPGGA:
- if(0 == (node->pack = malloc(sizeof(nmeaGPGGA))))
- goto mem_fail;
- node->packType = GPGGA;
- if(!nmea_parse_GPGGA(
- (const char *)parser->buffer + nparsed,
- sen_sz, (nmeaGPGGA *)node->pack))
- {
- free(node);
- node = 0;
- }
- break;
- case GPGSA:
- if(0 == (node->pack = malloc(sizeof(nmeaGPGSA))))
- goto mem_fail;
- node->packType = GPGSA;
- if(!nmea_parse_GPGSA(
- (const char *)parser->buffer + nparsed,
- sen_sz, (nmeaGPGSA *)node->pack))
- {
- free(node);
- node = 0;
- }
- break;
- case GPGSV:
- if(0 == (node->pack = malloc(sizeof(nmeaGPGSV))))
- goto mem_fail;
- node->packType = GPGSV;
- if(!nmea_parse_GPGSV(
- (const char *)parser->buffer + nparsed,
- sen_sz, (nmeaGPGSV *)node->pack))
- {
- free(node);
- node = 0;
- }
- break;
- case GPRMC:
- if(0 == (node->pack = malloc(sizeof(nmeaGPRMC))))
- goto mem_fail;
- node->packType = GPRMC;
- if(!nmea_parse_GPRMC(
- (const char *)parser->buffer + nparsed,
- sen_sz, (nmeaGPRMC *)node->pack))
- {
- free(node);
- node = 0;
- }
- break;
- case GPVTG:
- if(0 == (node->pack = malloc(sizeof(nmeaGPVTG))))
- goto mem_fail;
- node->packType = GPVTG;
- if(!nmea_parse_GPVTG(
- (const char *)parser->buffer + nparsed,
- sen_sz, (nmeaGPVTG *)node->pack))
- {
- free(node);
- node = 0;
- }
- break;
- default:
- free(node);
- node = 0;
- break;
- };
-
- if(node)
- {
- if(parser->end_node)
- ((nmeaParserNODE *)parser->end_node)->next_node = node;
- parser->end_node = node;
- if(!parser->top_node)
- parser->top_node = node;
- node->next_node = 0;
- }
- }
-
- nparsed += sen_sz;
- }
-
- return nparsed;
-
-mem_fail:
- if(node)
- free(node);
-
- nmea_error("Insufficient memory!");
-
- return -1;
-}
-
-/**
- * \brief Analysis of buffer and keep results into parser
- * @return Number of bytes wos parsed from buffer
- */
-int nmea_parser_push(nmeaPARSER *parser, const char *buff, int buff_sz)
-{
- int nparse, nparsed = 0;
-
- do
- {
- if(buff_sz > parser->buff_size)
- nparse = parser->buff_size;
- else
- nparse = buff_sz;
-
- nparsed += nmea_parser_real_push(
- parser, buff, nparse);
-
- buff_sz -= nparse;
-
- } while(buff_sz);
-
- return nparsed;
-}
-
-/**
- * \brief Get type of top packet keeped into parser
- * @return Type of packet
- * @see nmeaPACKTYPE
- */
-int nmea_parser_top(nmeaPARSER *parser)
-{
- int retval = GPNON;
- nmeaParserNODE *node = (nmeaParserNODE *)parser->top_node;
-
- //NMEA_ASSERT(parser && parser->buffer);
-
- if(node)
- retval = node->packType;
-
- return retval;
-}
-
-/**
- * \brief Withdraw top packet from parser
- * @return Received packet type
- * @see nmeaPACKTYPE
- */
-int nmea_parser_pop(nmeaPARSER *parser, void **pack_ptr)
-{
- int retval = GPNON;
- nmeaParserNODE *node = (nmeaParserNODE *)parser->top_node;
-
- //NMEA_ASSERT(parser && parser->buffer);
-
- if(node)
- {
- *pack_ptr = node->pack;
- retval = node->packType;
- parser->top_node = node->next_node;
- if(!parser->top_node)
- parser->end_node = 0;
- free(node);
- }
-
- return retval;
-}
-
-/**
- * \brief Get top packet from parser without withdraw
- * @return Received packet type
- * @see nmeaPACKTYPE
- */
-int nmea_parser_peek(nmeaPARSER *parser, void **pack_ptr)
-{
- int retval = GPNON;
- nmeaParserNODE *node = (nmeaParserNODE *)parser->top_node;
-
- //NMEA_ASSERT(parser && parser->buffer);
-
- if(node)
- {
- *pack_ptr = node->pack;
- retval = node->packType;
- }
-
- return retval;
-}
-
-/**
- * \brief Delete top packet from parser
- * @return Deleted packet type
- * @see nmeaPACKTYPE
- */
-int nmea_parser_drop(nmeaPARSER *parser)
-{
- int retval = GPNON;
- nmeaParserNODE *node = (nmeaParserNODE *)parser->top_node;
-
- //NMEA_ASSERT(parser && parser->buffer);
-
- if(node)
- {
- if(node->pack)
- free(node->pack);
- retval = node->packType;
- parser->top_node = node->next_node;
- if(!parser->top_node)
- parser->end_node = 0;
- free(node);
- }
-
- return retval;
-}
-
-/**
- * \brief Clear cache of parser
- * @return true (1) - success
- */
-int nmea_parser_buff_clear(nmeaPARSER *parser)
-{
- //NMEA_ASSERT(parser && parser->buffer);
- parser->buff_use = 0;
- return 1;
-}
-
-/**
- * \brief Clear packets queue into parser
- * @return true (1) - success
- */
-int nmea_parser_queue_clear(nmeaPARSER *parser)
-{
- //NMEA_ASSERT(parser);
- while(parser->top_node)
- nmea_parser_drop(parser);
- return 1;
-}
diff --git a/apps/gps/nmealib/sentence.c b/apps/gps/nmealib/sentence.c
deleted file mode 100644
index a66393a4d..000000000
--- a/apps/gps/nmealib/sentence.c
+++ /dev/null
@@ -1,54 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: sentence.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#include "nmea/sentence.h"
-
-#include <string.h>
-
-void nmea_zero_GPGGA(nmeaGPGGA *pack)
-{
- memset(pack, 0, sizeof(nmeaGPGGA));
- nmea_time_now(&pack->utc);
- pack->ns = 'N';
- pack->ew = 'E';
- pack->elv_units = 'M';
- pack->diff_units = 'M';
-}
-
-void nmea_zero_GPGSA(nmeaGPGSA *pack)
-{
- memset(pack, 0, sizeof(nmeaGPGSA));
- pack->fix_mode = 'A';
- pack->fix_type = NMEA_FIX_BAD;
-}
-
-void nmea_zero_GPGSV(nmeaGPGSV *pack)
-{
- memset(pack, 0, sizeof(nmeaGPGSV));
-}
-
-void nmea_zero_GPRMC(nmeaGPRMC *pack)
-{
- memset(pack, 0, sizeof(nmeaGPRMC));
- nmea_time_now(&pack->utc);
- pack->status = 'V';
- pack->ns = 'N';
- pack->ew = 'E';
- pack->declin_ew = 'E';
-}
-
-void nmea_zero_GPVTG(nmeaGPVTG *pack)
-{
- memset(pack, 0, sizeof(nmeaGPVTG));
- pack->dir_t = 'T';
- pack->dec_m = 'M';
- pack->spn_n = 'N';
- pack->spk_k = 'K';
-}
diff --git a/apps/gps/nmealib/time.c b/apps/gps/nmealib/time.c
deleted file mode 100644
index a24319630..000000000
--- a/apps/gps/nmealib/time.c
+++ /dev/null
@@ -1,63 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: time.c 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-/*! \file time.h */
-
-#include "nmea/time.h"
-
-#ifdef NMEA_WIN
-# pragma warning(disable: 4201)
-# pragma warning(disable: 4214)
-# pragma warning(disable: 4115)
-# include <windows.h>
-# pragma warning(default: 4201)
-# pragma warning(default: 4214)
-# pragma warning(default: 4115)
-#else
-# include <time.h>
-#endif
-
-#ifdef NMEA_WIN
-
-void nmea_time_now(nmeaTIME *stm)
-{
- SYSTEMTIME st;
-
- GetSystemTime(&st);
-
- stm->year = st.wYear - 1900;
- stm->mon = st.wMonth - 1;
- stm->day = st.wDay;
- stm->hour = st.wHour;
- stm->min = st.wMinute;
- stm->sec = st.wSecond;
- stm->hsec = st.wMilliseconds / 10;
-}
-
-#else /* NMEA_WIN */
-
-void nmea_time_now(nmeaTIME *stm)
-{
- time_t lt;
- struct tm *tt;
-
- time(&lt);
- tt = gmtime(&lt);
-
- stm->year = tt->tm_year;
- stm->mon = tt->tm_mon;
- stm->day = tt->tm_mday;
- stm->hour = tt->tm_hour;
- stm->min = tt->tm_min;
- stm->sec = tt->tm_sec;
- stm->hsec = 0;
-}
-
-#endif
diff --git a/apps/gps/nmealib/tok.c b/apps/gps/nmealib/tok.c
deleted file mode 100644
index c7cf2f4dc..000000000
--- a/apps/gps/nmealib/tok.c
+++ /dev/null
@@ -1,267 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: tok.c 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-/*! \file tok.h */
-
-#include "nmea/tok.h"
-
-#include <stdarg.h>
-#include <stdlib.h>
-#include <stdio.h>
-#include <ctype.h>
-#include <string.h>
-#include <limits.h>
-
-#define NMEA_TOKS_COMPARE (1)
-#define NMEA_TOKS_PERCENT (2)
-#define NMEA_TOKS_WIDTH (3)
-#define NMEA_TOKS_TYPE (4)
-
-//memchr replacement
-void *
-memchr(s, c, n)
- const void *s;
- unsigned char c;
- size_t n;
-{
- if (n != 0) {
- const unsigned char *p = s;
-
- do {
- if (*p++ == c)
- return ((void *)(p - 1));
- } while (--n != 0);
- }
- return (NULL);
-}
-
-
-/**
- * \brief Calculate control sum of binary buffer
- */
-int nmea_calc_crc(const char *buff, int buff_sz)
-{
- int chsum = 0,
- it;
-
- for(it = 0; it < buff_sz; ++it)
- chsum ^= (int)buff[it];
-
- return chsum;
-}
-
-/**
- * \brief Convert string to number
- */
-int nmea_atoi(const char *str, int str_sz, int radix)
-{
- char *tmp_ptr;
- char buff[NMEA_CONVSTR_BUF];
- int res = 0;
-
- if(str_sz < NMEA_CONVSTR_BUF)
- {
- memcpy(&buff[0], str, str_sz);
- buff[str_sz] = '\0';
- res = strtol(&buff[0], &tmp_ptr, radix);
- }
- return res;
-}
-
-/**
- * \brief Convert string to fraction number
- */
-float nmea_atof(const char *str, int str_sz)
-{
- char *tmp_ptr;
- char buff[NMEA_CONVSTR_BUF];
- float res = 0;
-
- if(str_sz < NMEA_CONVSTR_BUF)
- {
- memcpy(&buff[0], str, str_sz);
- buff[str_sz] = '\0';
- res = (float)strtod(&buff[0], &tmp_ptr);
- }
- return res;
-}
-
-/**
- * \brief Formating string (like standart printf) with CRC tail (*CRC)
- */
-int nmea_printf(char *buff, int buff_sz, const char *format, ...)
-{
- int retval, add = 0;
- va_list arg_ptr;
-
- if(buff_sz <= 0)
- return 0;
-
- va_start(arg_ptr, format);
-
- retval = NMEA_POSIX(vsnprintf)(buff, buff_sz, format, arg_ptr);
-
- if(retval > 0)
- {
- add = NMEA_POSIX(snprintf)(
- buff + retval, buff_sz - retval, "*%02x\r\n",
- nmea_calc_crc(buff + 1, retval - 1));
- }
-
- retval += add;
-
- if(retval < 0 || retval > buff_sz)
- {
- memset(buff, ' ', buff_sz);
- retval = buff_sz;
- }
-
- va_end(arg_ptr);
-
- return retval;
-}
-
-/**
- * \brief Analyse string (specificate for NMEA sentences)
- */
-int nmea_scanf(const char *buff, int buff_sz, const char *format, ...)
-{
- const char *beg_tok;
- const char *end_buf = buff + buff_sz;
-
- va_list arg_ptr;
- int tok_type = NMEA_TOKS_COMPARE;
- int width = 0;
- const char *beg_fmt = 0;
- int snum = 0, unum = 0;
-
- int tok_count = 0;
- void *parg_target;
-
- va_start(arg_ptr, format);
-
- for(; *format && buff < end_buf; ++format)
- {
- switch(tok_type)
- {
- case NMEA_TOKS_COMPARE:
- if('%' == *format)
- tok_type = NMEA_TOKS_PERCENT;
- else if(*buff++ != *format)
- goto fail;
- break;
- case NMEA_TOKS_PERCENT:
- width = 0;
- beg_fmt = format;
- tok_type = NMEA_TOKS_WIDTH;
- case NMEA_TOKS_WIDTH:
- if(isdigit(*format))
- break;
- {
- tok_type = NMEA_TOKS_TYPE;
- if(format > beg_fmt)
- width = nmea_atoi(beg_fmt, (int)(format - beg_fmt), 10);
- }
- case NMEA_TOKS_TYPE:
- beg_tok = buff;
-
- if(!width && ('c' == *format || 'C' == *format) && *buff != format[1])
- width = 1;
-
- if(width)
- {
- if(buff + width <= end_buf)
- buff += width;
- else
- goto fail;
- }
- else
- {
- if(!format[1] || (0 == (buff = (char *)memchr(buff, format[1], end_buf - buff))))
- buff = end_buf;
- }
-
- if(buff > end_buf)
- goto fail;
-
- tok_type = NMEA_TOKS_COMPARE;
- tok_count++;
-
- parg_target = 0; width = (int)(buff - beg_tok);
-
- switch(*format)
- {
- case 'c':
- case 'C':
- parg_target = (void *)va_arg(arg_ptr, char *);
- if(width && 0 != (parg_target))
- *((char *)parg_target) = *beg_tok;
- break;
- case 's':
- case 'S':
- parg_target = (void *)va_arg(arg_ptr, char *);
- if(width && 0 != (parg_target))
- {
- memcpy(parg_target, beg_tok, width);
- ((char *)parg_target)[width] = '\0';
- }
- break;
- case 'f':
- case 'g':
- case 'G':
- case 'e':
- case 'E':
- parg_target = (void *)va_arg(arg_ptr, float *);
- if(width && 0 != (parg_target))
- *((float *)parg_target) = nmea_atof(beg_tok, width);
- break;
- };
-
- if(parg_target)
- break;
- if(0 == (parg_target = (void *)va_arg(arg_ptr, int *)))
- break;
- if(!width)
- break;
-
- switch(*format)
- {
- case 'd':
- case 'i':
- snum = nmea_atoi(beg_tok, width, 10);
- memcpy(parg_target, &snum, sizeof(int));
- break;
- case 'u':
- unum = nmea_atoi(beg_tok, width, 10);
- memcpy(parg_target, &unum, sizeof(unsigned int));
- break;
- case 'x':
- case 'X':
- unum = nmea_atoi(beg_tok, width, 16);
- memcpy(parg_target, &unum, sizeof(unsigned int));
- break;
- case 'o':
- unum = nmea_atoi(beg_tok, width, 8);
- memcpy(parg_target, &unum, sizeof(unsigned int));
- break;
- default:
- goto fail;
- };
-
- break;
- };
- }
-
-fail:
-
- va_end(arg_ptr);
-
- return tok_count;
-}
diff --git a/apps/gps/ubx.c b/apps/gps/ubx.c
deleted file mode 100644
index b9f8a28a0..000000000
--- a/apps/gps/ubx.c
+++ /dev/null
@@ -1,1022 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- *
- * 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 PX4 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.
- *
- ****************************************************************************/
-
-/* @file U-Blox protocol implementation */
-
-
-#include "ubx.h"
-#include "gps.h"
-#include <sys/prctl.h>
-#include <poll.h>
-#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-#include <string.h>
-#include <stdbool.h>
-#include <fcntl.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <mavlink/mavlink_log.h>
-
-#define UBX_HEALTH_SUCCESS_COUNTER_LIMIT 2
-#define UBX_HEALTH_FAIL_COUNTER_LIMIT 3
-#define UBX_HEALTH_PROBE_COUNTER_LIMIT 4
-
-#define UBX_BUFFER_SIZE 500
-
-extern bool gps_mode_try_all;
-extern bool gps_mode_success;
-extern bool terminate_gps_thread;
-extern bool gps_baud_try_all;
-extern bool gps_verbose;
-extern int current_gps_speed;
-
-pthread_mutex_t *ubx_mutex;
-gps_bin_ubx_state_t *ubx_state;
-enum UBX_CONFIG_STATE ubx_config_state;
-static struct vehicle_gps_position_s *ubx_gps;
-
-
-
-void ubx_decode_init(void)
-{
- ubx_state->ck_a = 0;
- ubx_state->ck_b = 0;
- ubx_state->rx_count = 0;
- ubx_state->decode_state = UBX_DECODE_UNINIT;
- ubx_state->message_class = CLASS_UNKNOWN;
- ubx_state->message_id = ID_UNKNOWN;
- ubx_state->payload_size = 0;
- ubx_state->print_errors = false;
-}
-
-void ubx_checksum(uint8_t b, uint8_t *ck_a, uint8_t *ck_b)
-{
- *(ck_a) = *(ck_a) + b;
- *(ck_b) = *(ck_b) + *(ck_a);
-}
-
-
-
-
-
-int ubx_parse(uint8_t b, char *gps_rx_buffer)
-{
- //printf("b=%x\n",b);
- if (ubx_state->decode_state == UBX_DECODE_UNINIT) {
-
- if (b == UBX_SYNC_1) {
- ubx_state->decode_state = UBX_DECODE_GOT_SYNC1;
- }
-
- } else if (ubx_state->decode_state == UBX_DECODE_GOT_SYNC1) {
- if (b == UBX_SYNC_2) {
- ubx_state->decode_state = UBX_DECODE_GOT_SYNC2;
-
- } else {
- // Second start symbol was wrong, reset state machine
- ubx_decode_init();
- }
-
- } else if (ubx_state->decode_state == UBX_DECODE_GOT_SYNC2) {
- // Add to checksum
- ubx_checksum(b, &(ubx_state->ck_a), &(ubx_state->ck_b));
-
- //check for known class
- switch (b) {
- case UBX_CLASS_ACK:
- ubx_state->decode_state = UBX_DECODE_GOT_CLASS;
- ubx_state->message_class = ACK;
- break;
-
- case UBX_CLASS_NAV:
- ubx_state->decode_state = UBX_DECODE_GOT_CLASS;
- ubx_state->message_class = NAV;
- break;
-
- case UBX_CLASS_RXM:
- ubx_state->decode_state = UBX_DECODE_GOT_CLASS;
- ubx_state->message_class = RXM;
- break;
-
- case UBX_CLASS_CFG:
- ubx_state->decode_state = UBX_DECODE_GOT_CLASS;
- ubx_state->message_class = CFG;
- break;
- default: //unknown class: reset state machine
- ubx_decode_init();
- break;
- }
-
- } else if (ubx_state->decode_state == UBX_DECODE_GOT_CLASS) {
- // Add to checksum
- ubx_checksum(b, &(ubx_state->ck_a), &(ubx_state->ck_b));
-
- //depending on class look for message id
- switch (ubx_state->message_class) {
- case NAV:
- switch (b) {
- case UBX_MESSAGE_NAV_POSLLH: //NAV-POSLLH: Geodetic Position Solution
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = NAV_POSLLH;
- break;
-
- case UBX_MESSAGE_NAV_SOL:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = NAV_SOL;
- break;
-
- case UBX_MESSAGE_NAV_TIMEUTC:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = NAV_TIMEUTC;
- break;
-
- case UBX_MESSAGE_NAV_DOP:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = NAV_DOP;
- break;
-
- case UBX_MESSAGE_NAV_SVINFO:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = NAV_SVINFO;
- break;
-
- case UBX_MESSAGE_NAV_VELNED:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = NAV_VELNED;
- break;
-
- default: //unknown class: reset state machine, should not happen
- ubx_decode_init();
- break;
- }
-
- break;
-
- case RXM:
- switch (b) {
- case UBX_MESSAGE_RXM_SVSI:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = RXM_SVSI;
- break;
-
- default: //unknown class: reset state machine, should not happen
- ubx_decode_init();
- break;
- }
- break;
-
- case CFG:
- switch (b) {
- case UBX_MESSAGE_CFG_NAV5:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = CFG_NAV5;
- break;
-
- default: //unknown class: reset state machine, should not happen
- ubx_decode_init();
- break;
- }
- break;
-
- case ACK:
- switch (b) {
- case UBX_MESSAGE_ACK_ACK:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = ACK_ACK;
- break;
- case UBX_MESSAGE_ACK_NAK:
- ubx_state->decode_state = UBX_DECODE_GOT_MESSAGEID;
- ubx_state->message_id = ACK_NAK;
- break;
- default: //unknown class: reset state machine, should not happen
- ubx_decode_init();
- break;
- }
- break;
- default: //should not happen
- ubx_decode_init();
- break;
- }
-
- } else if (ubx_state->decode_state == UBX_DECODE_GOT_MESSAGEID) {
- // Add to checksum
- ubx_checksum(b, &(ubx_state->ck_a), &(ubx_state->ck_b));
-
- ubx_state->payload_size = b;
- ubx_state->decode_state = UBX_DECODE_GOT_LENGTH1;
-
- } else if (ubx_state->decode_state == UBX_DECODE_GOT_LENGTH1) {
- // Add to checksum
- ubx_checksum(b, &(ubx_state->ck_a), &(ubx_state->ck_b));
-
- ubx_state->payload_size += b << 8;
- ubx_state->decode_state = UBX_DECODE_GOT_LENGTH2;
-
- } else if (ubx_state->decode_state == UBX_DECODE_GOT_LENGTH2) {
- uint8_t ret = 0;
-
- // Add to checksum if not yet at checksum byte
- if (ubx_state->rx_count < ubx_state->payload_size) ubx_checksum(b, &(ubx_state->ck_a), &(ubx_state->ck_b));
-
- // Fill packet buffer
- gps_rx_buffer[ubx_state->rx_count] = b;
-
- //if whole payload + checksum is in buffer:
- if (ubx_state->rx_count >= ubx_state->payload_size + 1) {
- //convert to correct struct
- switch (ubx_state->message_id) { //this enum is unique for all ids --> no need to check the class
- case NAV_POSLLH: {
-// printf("GOT NAV_POSLLH MESSAGE\n");
- gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid and the store the gps information
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
- ubx_gps->lat = packet->lat;
- ubx_gps->lon = packet->lon;
- ubx_gps->alt = packet->height_msl;
-
- ubx_gps->counter_pos_valid++;
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[NAV_POSLLH - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] NAV_POSLLH: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case NAV_SOL: {
-// printf("GOT NAV_SOL MESSAGE\n");
- gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid and the store the gps information
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
-
- ubx_gps->fix_type = packet->gpsFix;
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
- ubx_gps->s_variance = packet->sAcc;
- ubx_gps->p_variance = packet->pAcc;
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[NAV_SOL - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] NAV_SOL: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case NAV_DOP: {
-// printf("GOT NAV_DOP MESSAGE\n");
- gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid and the store the gps information
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
-
- ubx_gps->eph = packet->hDOP;
- ubx_gps->epv = packet->vDOP;
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
-
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[NAV_DOP - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] NAV_DOP: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case NAV_TIMEUTC: {
-// printf("GOT NAV_TIMEUTC MESSAGE\n");
- gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid and the store the gps information
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
- //convert to unix timestamp
- struct tm timeinfo;
- timeinfo.tm_year = packet->year - 1900;
- timeinfo.tm_mon = packet->month - 1;
- timeinfo.tm_mday = packet->day;
- timeinfo.tm_hour = packet->hour;
- timeinfo.tm_min = packet->min;
- timeinfo.tm_sec = packet->sec;
-
- time_t epoch = mktime(&timeinfo);
-
-// printf("%d.%d.%d %d:%d:%d:%d\n", timeinfo.tm_year, timeinfo.tm_mon, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec, packet->time_nanoseconds);
-
-
-
- ubx_gps->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
- ubx_gps->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
-
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[NAV_TIMEUTC - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("\t[gps] NAV_TIMEUTC: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case NAV_SVINFO: {
-// printf("GOT NAV_SVINFO MESSAGE\n");
-
- //this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message
- const int length_part1 = 8;
- char gps_rx_buffer_part1[length_part1];
- memcpy(gps_rx_buffer_part1, gps_rx_buffer, length_part1);
- gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) gps_rx_buffer_part1;
-
- //read checksum
- const int length_part3 = 2;
- char gps_rx_buffer_part3[length_part3];
- memcpy(gps_rx_buffer_part3, &(gps_rx_buffer[ubx_state->rx_count - 1]), length_part3);
- gps_bin_nav_svinfo_part3_packet_t *packet_part3 = (gps_bin_nav_svinfo_part3_packet_t *) gps_rx_buffer_part3;
-
- //Check if checksum is valid and then store the gps information
- if (ubx_state->ck_a == packet_part3->ck_a && ubx_state->ck_b == packet_part3->ck_b) {
- //definitions needed to read numCh elements from the buffer:
- const int length_part2 = 12;
- gps_bin_nav_svinfo_part2_packet_t *packet_part2;
- char gps_rx_buffer_part2[length_part2]; //for temporal storage
-
-
- int i;
-
- for (i = 0; i < packet_part1->numCh; i++) { //for each channel
-
- /* Get satellite information from the buffer */
-
- memcpy(gps_rx_buffer_part2, &(gps_rx_buffer[length_part1 + i * length_part2]), length_part2);
- packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) gps_rx_buffer_part2;
-
-
- /* Write satellite information in the global storage */
-
- ubx_gps->satellite_prn[i] = packet_part2->svid;
-
- //if satellite information is healthy store the data
- uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield
-
- if (!unhealthy) {
-
- if ((packet_part2->flags) & 1) { //flags is a bitfield
- ubx_gps->satellite_used[i] = 1;
-
- } else {
- ubx_gps->satellite_used[i] = 0;
- }
-
- ubx_gps->satellite_snr[i] = packet_part2->cno;
- ubx_gps->satellite_elevation[i] = (uint8_t)(packet_part2->elev);
- ubx_gps->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f);
-
- } else {
- ubx_gps->satellite_used[i] = 0;
- ubx_gps->satellite_snr[i] = 0;
- ubx_gps->satellite_elevation[i] = 0;
- ubx_gps->satellite_azimuth[i] = 0;
- }
-
- }
-
- for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused
- /* Unused channels have to be set to zero for e.g. MAVLink */
- ubx_gps->satellite_prn[i] = 0;
- ubx_gps->satellite_used[i] = 0;
- ubx_gps->satellite_snr[i] = 0;
- ubx_gps->satellite_elevation[i] = 0;
- ubx_gps->satellite_azimuth[i] = 0;
- }
-
- /* set flag if any sat info is available */
- if (!packet_part1->numCh > 0) {
- ubx_gps->satellite_info_available = 1;
-
- } else {
- ubx_gps->satellite_info_available = 0;
- }
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
-
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[NAV_SVINFO - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("\t[gps] NAV_SVINFO: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case NAV_VELNED: {
-// printf("GOT NAV_VELNED MESSAGE\n");
- gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid and the store the gps information
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
-
- ubx_gps->vel = (uint16_t)packet->speed;
- ubx_gps->vel_n = packet->velN / 100.0f;
- ubx_gps->vel_e = packet->velE / 100.0f;
- ubx_gps->vel_d = packet->velD / 100.0f;
- ubx_gps->vel_ned_valid = true;
- ubx_gps->cog = (uint16_t)((float)(packet->heading) * 1e-3f);
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
-
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[NAV_VELNED - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] NAV_VELNED: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case RXM_SVSI: {
-// printf("GOT RXM_SVSI MESSAGE\n");
- const int length_part1 = 7;
- char gps_rx_buffer_part1[length_part1];
- memcpy(gps_rx_buffer_part1, gps_rx_buffer, length_part1);
- gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) gps_rx_buffer_part1;
-
- //Check if checksum is valid and the store the gps information
- if (ubx_state->ck_a == gps_rx_buffer[ubx_state->rx_count - 1] && ubx_state->ck_b == gps_rx_buffer[ubx_state->rx_count]) {
-
- ubx_gps->satellites_visible = packet->numVis;
-
- ubx_gps->timestamp = hrt_absolute_time();
- ubx_gps->counter++;
-
-
- //pthread_mutex_lock(ubx_mutex);
- ubx_state->last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time();
- //pthread_mutex_unlock(ubx_mutex);
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] RXM_SVSI: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case ACK_ACK: {
-// printf("GOT ACK_ACK\n");
- gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
-
- switch (ubx_config_state) {
- case UBX_CONFIG_STATE_PRT:
- if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_PRT)
- ubx_config_state++;
- break;
- case UBX_CONFIG_STATE_NAV5:
- if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_NAV5)
- ubx_config_state++;
- break;
- case UBX_CONFIG_STATE_MSG_NAV_POSLLH:
- case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC:
- case UBX_CONFIG_STATE_MSG_NAV_DOP:
- case UBX_CONFIG_STATE_MSG_NAV_SVINFO:
- case UBX_CONFIG_STATE_MSG_NAV_SOL:
- case UBX_CONFIG_STATE_MSG_NAV_VELNED:
- case UBX_CONFIG_STATE_MSG_RXM_SVSI:
- if (packet->clsID == UBX_CLASS_CFG && packet->msgID == UBX_MESSAGE_CFG_MSG)
- ubx_config_state++;
- break;
- default:
- break;
- }
-
-
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] ACK_ACK: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- case ACK_NAK: {
-// printf("GOT ACK_NAK\n");
- gps_bin_ack_nak_packet_t *packet = (gps_bin_ack_nak_packet_t *) gps_rx_buffer;
-
- //Check if checksum is valid
- if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
-
- if (gps_verbose) printf("[gps] the ubx gps returned: not acknowledged\n");
- ret = 1;
-
- } else {
- if (gps_verbose) printf("[gps] ACK_NAK: checksum invalid\n");
-
- ret = 0;
- }
-
- // Reset state machine to decode next packet
- ubx_decode_init();
- return ret;
-
- break;
- }
-
- default: //something went wrong
- ubx_decode_init();
-
- break;
- }
- }
-
- (ubx_state->rx_count)++;
-
-
-
- }
-
-
- return 0; // no valid packet found
-
-}
-
-void calculate_ubx_checksum(uint8_t *message, uint8_t length)
-{
- uint8_t ck_a = 0;
- uint8_t ck_b = 0;
-
- int i;
-
- for (i = 2; i < length - 2; i++) {
- ck_a = ck_a + message[i];
- ck_b = ck_b + ck_a;
- }
-
- message[length - 2] = ck_a;
- message[length - 1] = ck_b;
-}
-
-int configure_gps_ubx(int *fd)
-{
- // only needed once like this
- const type_gps_bin_cfg_prt_packet_t cfg_prt_packet = {
- .clsID = UBX_CLASS_CFG,
- .msgID = UBX_MESSAGE_CFG_PRT,
- .length = UBX_CFG_PRT_LENGTH,
- .portID = UBX_CFG_PRT_PAYLOAD_PORTID,
- .mode = UBX_CFG_PRT_PAYLOAD_MODE,
- .baudRate = current_gps_speed,
- .inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK,
- .outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK,
- .ck_a = 0,
- .ck_b = 0
- };
-
- // only needed once like this
- const type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet = {
- .clsID = UBX_CLASS_CFG,
- .msgID = UBX_MESSAGE_CFG_NAV5,
- .length = UBX_CFG_NAV5_LENGTH,
- .mask = UBX_CFG_NAV5_PAYLOAD_MASK,
- .dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL,
- .fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE,
- .ck_a = 0,
- .ck_b = 0
- };
-
- // this message is reusable for different configuration commands, so not const
- type_gps_bin_cfg_msg_packet cfg_msg_packet = {
- .clsID = UBX_CLASS_CFG,
- .msgID = UBX_MESSAGE_CFG_MSG,
- .length = UBX_CFG_MSG_LENGTH,
- .rate = UBX_CFG_MSG_PAYLOAD_RATE
- };
-
- uint64_t time_before_config = hrt_absolute_time();
-
- while(hrt_absolute_time() < time_before_config + UBX_CONFIG_TIMEOUT) {
-
-// if (gps_verbose) printf("[gps] ubx config state: %d\n", ubx_config_state);
-
- switch (ubx_config_state) {
- case UBX_CONFIG_STATE_PRT:
-// if (gps_verbose) printf("[gps] Configuring ubx with baudrate: %d\n", cfg_prt_packet.baudRate);
-
- write_config_message_ubx((uint8_t*)(&cfg_prt_packet), sizeof(cfg_prt_packet), fd);
- break;
- case UBX_CONFIG_STATE_NAV5:
- write_config_message_ubx((uint8_t*)(&cfg_nav5_packet), sizeof(cfg_nav5_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_NAV_POSLLH:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_NAV_TIMEUTC:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_NAV_DOP:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_NAV_SVINFO:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_NAV_SOL:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_NAV_VELNED:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_MSG_RXM_SVSI:
- cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM;
- cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI;
- write_config_message_ubx((uint8_t*)(&cfg_msg_packet), sizeof(cfg_msg_packet), fd);
- break;
- case UBX_CONFIG_STATE_CONFIGURED:
- if (gps_verbose) printf("[gps] ubx configuration finished\n");
- return OK;
- break;
- default:
- break;
- }
- usleep(10000);
- }
- if (gps_verbose) printf("[gps] ubx configuration timeout\n");
- return ERROR;
-}
-
-
-
-int read_gps_ubx(int *fd, char *gps_rx_buffer, int buffer_size)
-{
- uint8_t ret = 0;
- uint8_t c;
- int rx_count = 0;
- int gpsRxOverflow = 0;
-
- struct pollfd fds;
- fds.fd = *fd;
- fds.events = POLLIN;
-
- // UBX GPS mode
- // This blocks the task until there is something on the buffer
- while (1) {
- //check if the thread should terminate
- if (terminate_gps_thread == true) {
- ret = 1;
- break;
- }
- if (poll(&fds, 1, 1000) > 0) {
- if (read(*fd, &c, 1) > 0) {
-
-// printf("Read %x\n",c);
- if (rx_count >= buffer_size) {
- // The buffer is already full and we haven't found a valid ubx sentence.
- // Flush the buffer and note the overflow event.
- gpsRxOverflow++;
- rx_count = 0;
- ubx_decode_init();
-
- if (gps_verbose) printf("[gps] Buffer full\n");
-
- } else {
- //gps_rx_buffer[rx_count] = c;
- rx_count++;
-
- }
-
- int msg_read = ubx_parse(c, gps_rx_buffer);
-
- if (msg_read > 0) {
- //printf("Found sequence\n");
- break;
- }
-
- } else {
- break;
- }
-
- } else {
- break;
- }
-
- }
-
- return ret;
-}
-
-int write_config_message_ubx(const uint8_t *message, const size_t length, const int *fd)
-{
- uint8_t ck_a = 0;
- uint8_t ck_b = 0;
-
- unsigned int i;
-
- uint8_t buffer[2];
- ssize_t result_write = 0;
-
- //calculate and write checksum to the end
- for (i = 0; i < length-2; i++) {
- ck_a = ck_a + message[i];
- ck_b = ck_b + ck_a;
- }
-
- // write sync bytes first
- buffer[0] = UBX_SYNC_1;
- buffer[1] = UBX_SYNC_2;
-
- // write config message without the checksum
- result_write = write(*fd, buffer, sizeof(buffer));
- result_write += write(*fd, message, length-2);
-
- buffer[0] = ck_a;
- buffer[1] = ck_b;
-
- // write the checksum
- result_write += write(*fd, buffer, sizeof(buffer));
-
- fsync(*fd);
- if ((unsigned int)result_write != length + 2)
- return ERROR;
-
- return OK;
-}
-
-void *ubx_watchdog_loop(void *args)
-{
- /* Set thread name */
- prctl(PR_SET_NAME, "gps ubx watchdog", getpid());
-
-
- /* Retrieve file descriptor and thread flag */
- struct arg_struct *arguments = (struct arg_struct *)args;
- int *fd = arguments->fd_ptr;
- bool *thread_should_exit = arguments->thread_should_exit_ptr;
-
- ubx_config_state = UBX_CONFIG_STATE_PRT;
- /* first try to configure the GPS anyway */
- configure_gps_ubx(fd);
-
- /* GPS watchdog error message skip counter */
-
- bool ubx_healthy = false;
-
- uint8_t ubx_fail_count = 0;
- uint8_t ubx_success_count = 0;
- bool once_ok = false;
-
- int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
- //int err_skip_counter = 0;
-
- while (!(*thread_should_exit)) {
- /* if some values are to old reconfigure gps */
- int i;
- pthread_mutex_lock(ubx_mutex);
- bool all_okay = true;
- uint64_t timestamp_now = hrt_absolute_time();
-
- for (i = 0; i < UBX_NO_OF_MESSAGES; i++) {
-// printf("timestamp_now=%llu\n", timestamp_now);
-// printf("last_message_timestamps=%llu\n", ubx_state->last_message_timestamps[i]);
- if (timestamp_now - ubx_state->last_message_timestamps[i] > UBX_WATCHDOG_CRITICAL_TIME_MICROSECONDS) {
- //printf("Warning: GPS ubx message %d not received for a long time\n", i);
- all_okay = false;
- }
- }
-
- pthread_mutex_unlock(ubx_mutex);
-
- if (!all_okay) {
- /* gps error */
- ubx_fail_count++;
-// if (err_skip_counter == 0)
-// {
-// printf("GPS Watchdog detected gps not running or having problems\n");
-// err_skip_counter = 20;
-// }
-// err_skip_counter--;
- //printf("gps_mode_try_all =%u, ubx_fail_count=%u, ubx_healthy=%u, once_ok=%u\n", gps_mode_try_all, ubx_fail_count, ubx_healthy, once_ok);
-
-
- /* If we have too many failures and another mode or baud should be tried, exit... */
- if ((gps_mode_try_all == true || gps_baud_try_all == true) && (ubx_fail_count >= UBX_HEALTH_PROBE_COUNTER_LIMIT) && (ubx_healthy == false) && once_ok == false) {
- if (gps_verbose) printf("[gps] Connection attempt failed, no UBX module found\n");
-
- gps_mode_success = false;
- break;
- }
-
- if (ubx_healthy && ubx_fail_count == UBX_HEALTH_FAIL_COUNTER_LIMIT) {
- printf("[gps] ERROR: UBX GPS module stopped responding\n");
- // global_data_send_subsystem_info(&ubx_present_enabled);
- mavlink_log_critical(mavlink_fd, "[gps] UBX module stopped responding\n");
- ubx_healthy = false;
- ubx_success_count = 0;
- }
-
- /* trying to reconfigure the gps configuration */
- ubx_config_state = UBX_CONFIG_STATE_PRT;
- configure_gps_ubx(fd);
- fflush(stdout);
- sleep(1);
-
- } else {
- /* gps healthy */
- ubx_success_count++;
- ubx_fail_count = 0;
- once_ok = true; // XXX Should this be true on a single success, or on same criteria as ubx_healthy?
-
- if (!ubx_healthy && ubx_success_count == UBX_HEALTH_SUCCESS_COUNTER_LIMIT) {
- //printf("[gps] ublox UBX module status ok (baud=%d)\r\n", current_gps_speed);
- // global_data_send_subsystem_info(&ubx_present_enabled_healthy);
- mavlink_log_info(mavlink_fd, "[gps] UBX module found, status ok\n");
- ubx_healthy = true;
- }
- }
- usleep(UBX_WATCHDOG_WAIT_TIME_MICROSECONDS);
- }
-
- if(gps_verbose) printf("[gps] ubx loop is going to terminate\n");
- close(mavlink_fd);
- return NULL;
-}
-
-void *ubx_loop(void *args)
-{
- /* Set thread name */
- prctl(PR_SET_NAME, "gps ubx read", getpid());
-
- /* Retrieve file descriptor and thread flag */
- struct arg_struct *arguments = (struct arg_struct *)args;
- int *fd = arguments->fd_ptr;
- bool *thread_should_exit = arguments->thread_should_exit_ptr;
-
- /* Initialize gps stuff */
- char gps_rx_buffer[UBX_BUFFER_SIZE];
-
-
- if (gps_verbose) printf("[gps] UBX protocol driver starting..\n");
-
- //set parameters for ubx_state
-
- //ubx state
- ubx_state = malloc(sizeof(gps_bin_ubx_state_t));
- //printf("gps: ubx_state created\n");
- ubx_decode_init();
- ubx_state->print_errors = false;
-
-
- /* set parameters for ubx */
-
- struct vehicle_gps_position_s ubx_gps_d = {.counter = 0};
-
- ubx_gps = &ubx_gps_d;
-
- orb_advert_t gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &ubx_gps);
-
- while (!(*thread_should_exit)) {
- /* Parse a message from the gps receiver */
- if (0 == read_gps_ubx(fd, gps_rx_buffer, UBX_BUFFER_SIZE)) {
- /* publish new GPS position */
- orb_publish(ORB_ID(vehicle_gps_position), gps_pub, ubx_gps);
-
- } else {
- /* de-advertise */
- close(gps_pub);
- break;
- }
- }
-
- if(gps_verbose) printf("[gps] ubx read is going to terminate\n");
- close(gps_pub);
- return NULL;
-
-}
diff --git a/apps/gps/ubx.h b/apps/gps/ubx.h
deleted file mode 100644
index f3313a3c6..000000000
--- a/apps/gps/ubx.h
+++ /dev/null
@@ -1,415 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- *
- * 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 PX4 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.
- *
- ****************************************************************************/
-
-/* @file U-Blox protocol definitions */
-
-#ifndef UBX_H_
-#define UBX_H_
-
-#include <stdint.h>
-#include <stdlib.h>
-#include <stdio.h>
-#include <time.h>
-#include <math.h>
-#include <stdbool.h>
-#include <unistd.h>
-#include <pthread.h>
-
-
-//internal definitions (not depending on the ubx protocol
-#define UBX_NO_OF_MESSAGES 7 /**< Read 7 UBX GPS messages */
-#define UBX_WATCHDOG_CRITICAL_TIME_MICROSECONDS 3000000 /**< Allow 3 seconds maximum inter-message time */
-#define UBX_WATCHDOG_WAIT_TIME_MICROSECONDS 2000000 /**< Check for current state every two seconds */
-
-#define UBX_CONFIG_TIMEOUT 1000000
-
-#define APPNAME "gps: ubx"
-
-#define UBX_SYNC_1 0xB5
-#define UBX_SYNC_2 0x62
-
-//UBX Protocoll definitions (this is the subset of the messages that are parsed)
-#define UBX_CLASS_NAV 0x01
-#define UBX_CLASS_RXM 0x02
-#define UBX_CLASS_ACK 0x05
-#define UBX_CLASS_CFG 0x06
-#define UBX_MESSAGE_NAV_POSLLH 0x02
-#define UBX_MESSAGE_NAV_SOL 0x06
-#define UBX_MESSAGE_NAV_TIMEUTC 0x21
-#define UBX_MESSAGE_NAV_DOP 0x04
-#define UBX_MESSAGE_NAV_SVINFO 0x30
-#define UBX_MESSAGE_NAV_VELNED 0x12
-#define UBX_MESSAGE_RXM_SVSI 0x20
-#define UBX_MESSAGE_ACK_ACK 0x01
-#define UBX_MESSAGE_ACK_NAK 0x00
-#define UBX_MESSAGE_CFG_PRT 0x00
-#define UBX_MESSAGE_CFG_NAV5 0x24
-#define UBX_MESSAGE_CFG_MSG 0x01
-
-#define UBX_CFG_PRT_LENGTH 20
-#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< port 1 */
-#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
-#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */
-#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< ubx in */
-#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< ubx out */
-
-#define UBX_CFG_NAV5_LENGTH 36
-#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0001 /**< only update dynamic model and fix mode */
-#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */
-#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */
-
-#define UBX_CFG_MSG_LENGTH 8
-#define UBX_CFG_MSG_PAYLOAD_RATE {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} /**< UART1 chosen */
-
-
-// ************
-/** the structures of the binary packets */
-#pragma pack(push, 1)
-typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- int32_t lon; // Longitude * 1e-7, deg
- int32_t lat; // Latitude * 1e-7, deg
- int32_t height; // Height above Ellipsoid, mm
- int32_t height_msl; // Height above mean sea level, mm
- uint32_t hAcc; // Horizontal Accuracy Estimate, mm
- uint32_t vAcc; // Vertical Accuracy Estimate, mm
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_nav_posllh_packet;
-
-typedef type_gps_bin_nav_posllh_packet gps_bin_nav_posllh_packet_t;
-
-typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- int32_t time_nanoseconds; // Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000
- int16_t week; // GPS week (GPS time)
- uint8_t gpsFix; //GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix
- uint8_t flags;
- int32_t ecefX;
- int32_t ecefY;
- int32_t ecefZ;
- uint32_t pAcc;
- int32_t ecefVX;
- int32_t ecefVY;
- int32_t ecefVZ;
- uint32_t sAcc;
- uint16_t pDOP;
- uint8_t reserved1;
- uint8_t numSV;
- uint32_t reserved2;
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_nav_sol_packet;
-
-typedef type_gps_bin_nav_sol_packet gps_bin_nav_sol_packet_t;
-
-typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- uint32_t time_accuracy; //Time Accuracy Estimate, ns
- int32_t time_nanoseconds; //Nanoseconds of second, range -1e9 .. 1e9 (UTC)
- uint16_t year; //Year, range 1999..2099 (UTC)
- uint8_t month; //Month, range 1..12 (UTC)
- uint8_t day; //Day of Month, range 1..31 (UTC)
- uint8_t hour; //Hour of Day, range 0..23 (UTC)
- uint8_t min; //Minute of Hour, range 0..59 (UTC)
- uint8_t sec; //Seconds of Minute, range 0..59 (UTC)
- uint8_t valid_flag; //Validity Flags (see ubx documentation)
-
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_nav_timeutc_packet;
-
-typedef type_gps_bin_nav_timeutc_packet gps_bin_nav_timeutc_packet_t;
-
-typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- uint16_t gDOP; //Geometric DOP (scaling 0.01)
- uint16_t pDOP; //Position DOP (scaling 0.01)
- uint16_t tDOP; //Time DOP (scaling 0.01)
- uint16_t vDOP; //Vertical DOP (scaling 0.01)
- uint16_t hDOP; //Horizontal DOP (scaling 0.01)
- uint16_t nDOP; //Northing DOP (scaling 0.01)
- uint16_t eDOP; //Easting DOP (scaling 0.01)
-
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_nav_dop_packet;
-
-typedef type_gps_bin_nav_dop_packet gps_bin_nav_dop_packet_t;
-
-typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- uint8_t numCh; //Number of channels
- uint8_t globalFlags;
- uint16_t reserved2;
-
-} type_gps_bin_nav_svinfo_part1_packet;
-
-typedef type_gps_bin_nav_svinfo_part1_packet gps_bin_nav_svinfo_part1_packet_t;
-
-typedef struct {
- uint8_t chn; //Channel number, 255 for SVs not assigned to a channel
- uint8_t svid; //Satellite ID
- uint8_t flags;
- uint8_t quality;
- uint8_t cno; //Carrier to Noise Ratio (Signal Strength), dbHz
- int8_t elev; //Elevation in integer degrees
- int16_t azim; //Azimuth in integer degrees
- int32_t prRes; //Pseudo range residual in centimetres
-
-} type_gps_bin_nav_svinfo_part2_packet;
-
-typedef type_gps_bin_nav_svinfo_part2_packet gps_bin_nav_svinfo_part2_packet_t;
-
-typedef struct {
- uint8_t ck_a;
- uint8_t ck_b;
-
-} type_gps_bin_nav_svinfo_part3_packet;
-
-typedef type_gps_bin_nav_svinfo_part3_packet gps_bin_nav_svinfo_part3_packet_t;
-
-
-typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- int32_t velN; //NED north velocity, cm/s
- int32_t velE; //NED east velocity, cm/s
- int32_t velD; //NED down velocity, cm/s
- uint32_t speed; //Speed (3-D), cm/s
- uint32_t gSpeed; //Ground Speed (2-D), cm/s
- int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5
- uint32_t sAcc; //Speed Accuracy Estimate, cm/s
- uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_nav_velned_packet;
-
-typedef type_gps_bin_nav_velned_packet gps_bin_nav_velned_packet_t;
-
-typedef struct {
- int32_t time_milliseconds; // Measurement integer millisecond GPS time of week
- int16_t week; //Measurement GPS week number
- uint8_t numVis; //Number of visible satellites
-
- //... rest of package is not used in this implementation
-
-} type_gps_bin_rxm_svsi_packet;
-
-typedef type_gps_bin_rxm_svsi_packet gps_bin_rxm_svsi_packet_t;
-
-typedef struct {
- uint8_t clsID;
- uint8_t msgID;
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_ack_ack_packet;
-
-typedef type_gps_bin_ack_ack_packet gps_bin_ack_ack_packet_t;
-
-typedef struct {
- uint8_t clsID;
- uint8_t msgID;
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_ack_nak_packet;
-
-typedef type_gps_bin_ack_nak_packet gps_bin_ack_nak_packet_t;
-
-typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint8_t portID;
- uint8_t res0;
- uint16_t res1;
- uint32_t mode;
- uint32_t baudRate;
- uint16_t inProtoMask;
- uint16_t outProtoMask;
- uint16_t flags;
- uint16_t pad;
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_prt_packet;
-
-typedef type_gps_bin_cfg_prt_packet type_gps_bin_cfg_prt_packet_t;
-
-typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint16_t mask;
- uint8_t dynModel;
- uint8_t fixMode;
- int32_t fixedAlt;
- uint32_t fixedAltVar;
- int8_t minElev;
- uint8_t drLimit;
- uint16_t pDop;
- uint16_t tDop;
- uint16_t pAcc;
- uint16_t tAcc;
- uint8_t staticHoldThresh;
- uint8_t dgpsTimeOut;
- uint32_t reserved2;
- uint32_t reserved3;
- uint32_t reserved4;
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_nav5_packet;
-
-typedef type_gps_bin_cfg_nav5_packet type_gps_bin_cfg_nav5_packet_t;
-
-typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint8_t msgClass_payload;
- uint8_t msgID_payload;
- uint8_t rate[6];
-
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_msg_packet;
-
-typedef type_gps_bin_cfg_msg_packet type_gps_bin_cfg_msg_packet_t;
-
-
-// END the structures of the binary packets
-// ************
-
-enum UBX_CONFIG_STATE {
- UBX_CONFIG_STATE_NONE = 0,
- UBX_CONFIG_STATE_PRT = 1,
- UBX_CONFIG_STATE_NAV5 = 2,
- UBX_CONFIG_STATE_MSG_NAV_POSLLH = 3,
- UBX_CONFIG_STATE_MSG_NAV_TIMEUTC = 4,
- UBX_CONFIG_STATE_MSG_NAV_DOP = 5,
- UBX_CONFIG_STATE_MSG_NAV_SVINFO = 6,
- UBX_CONFIG_STATE_MSG_NAV_SOL = 7,
- UBX_CONFIG_STATE_MSG_NAV_VELNED = 8,
- UBX_CONFIG_STATE_MSG_RXM_SVSI = 9,
- UBX_CONFIG_STATE_CONFIGURED = 10
-};
-
-enum UBX_MESSAGE_CLASSES {
- CLASS_UNKNOWN = 0,
- NAV = 1,
- RXM = 2,
- ACK = 3,
- CFG = 4
-};
-
-enum UBX_MESSAGE_IDS {
- //these numbers do NOT correspond to the message id numbers of the ubx protocol
- ID_UNKNOWN = 0,
- NAV_POSLLH = 1,
- NAV_SOL = 2,
- NAV_TIMEUTC = 3,
- NAV_DOP = 4,
- NAV_SVINFO = 5,
- NAV_VELNED = 6,
- RXM_SVSI = 7,
- CFG_NAV5 = 8,
- ACK_ACK = 9,
- ACK_NAK = 10
-};
-
-enum UBX_DECODE_STATES {
- UBX_DECODE_UNINIT = 0,
- UBX_DECODE_GOT_SYNC1 = 1,
- UBX_DECODE_GOT_SYNC2 = 2,
- UBX_DECODE_GOT_CLASS = 3,
- UBX_DECODE_GOT_MESSAGEID = 4,
- UBX_DECODE_GOT_LENGTH1 = 5,
- UBX_DECODE_GOT_LENGTH2 = 6
-};
-
-typedef struct {
- union {
- uint16_t ck;
- struct {
- uint8_t ck_a;
- uint8_t ck_b;
- };
- };
- enum UBX_DECODE_STATES decode_state;
- bool print_errors;
- int16_t rx_count;
- uint16_t payload_size;
-
- enum UBX_MESSAGE_CLASSES message_class;
- enum UBX_MESSAGE_IDS message_id;
- uint64_t last_message_timestamps[UBX_NO_OF_MESSAGES];
-
-} type_gps_bin_ubx_state;
-
-typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
-#pragma pack(pop)
-
-extern pthread_mutex_t *ubx_mutex;
-extern gps_bin_ubx_state_t *ubx_state;
-
-void ubx_decode_init(void);
-
-void ubx_checksum(uint8_t b, uint8_t *ck_a, uint8_t *ck_b);
-
-
-
-int ubx_parse(uint8_t b, char *gps_rx_buffer);
-
-int configure_gps_ubx(int *fd);
-
-int read_gps_ubx(int *fd, char *gps_rx_buffer, int buffer_size);
-
-int write_config_message_ubx(const uint8_t *message, const size_t length, const int *fd);
-
-void calculate_ubx_checksum(uint8_t *message, uint8_t length);
-
-void *ubx_watchdog_loop(void *args);
-
-void *ubx_loop(void *args);
-
-
-#endif /* UBX_H_ */
diff --git a/apps/include/nsh.h b/apps/include/nsh.h
index 4b5a3cd31..8e469a555 100644
--- a/apps/include/nsh.h
+++ b/apps/include/nsh.h
@@ -1,7 +1,7 @@
/****************************************************************************
* apps/include/nsh.h
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -45,6 +45,31 @@
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
+/* If a USB device is selected for the NSH console then we need to handle some
+ * special start-up conditions.
+ */
+
+#undef HAVE_USB_CONSOLE
+#if defined(CONFIG_USBDEV)
+
+/* Check for a PL2303 serial console. Use console device "/dev/console". */
+
+# if defined(CONFIG_PL2303) && defined(CONFIG_PL2303_CONSOLE)
+# define HAVE_USB_CONSOLE 1
+
+/* Check for a CDC/ACM serial console. Use console device "/dev/console". */
+
+# elif defined(CONFIG_CDCACM) && defined(CONFIG_CDCACM_CONSOLE)
+# define HAVE_USB_CONSOLE 1
+
+/* Check for a generic USB console. In this case, the USB console device
+ * must be provided in CONFIG_NSH_CONDEV.
+ */
+
+# elif defined(CONFIG_NSH_USBCONSOLE)
+# define HAVE_USB_CONSOLE 1
+# endif
+#endif
#if CONFIG_RR_INTERVAL > 0
# define SCHED_NSH SCHED_RR
@@ -58,7 +83,8 @@
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -83,35 +109,54 @@ extern "C" {
*
****************************************************************************/
-EXTERN void nsh_initialize(void);
+void nsh_initialize(void);
/****************************************************************************
* Name: nsh_consolemain
*
* Description:
* This interfaces maybe to called or started with task_start to start a
- * single an NSH instance that operates on stdin and stdout (/dev/console).
- * This function does not return.
+ * single an NSH instance that operates on stdin and stdout. This
+ * function does not return.
*
+ * This function handles generic /dev/console character devices, or
+ * special USB console devices. The USB console requires some special
+ * operations to handle the cases where the session is lost when the
+ * USB device is unplugged and restarted when the USB device is plugged
+ * in again.
+ *
* Input Parameters:
- * Standard task start-up arguements. These are not used. argc may be
+ * Standard task start-up arguments. These are not used. argc may be
* zero and argv may be NULL.
*
* Returned Values:
* This function does not normally return. exit() is usually called to
* terminate the NSH session. This function will return in the event of
- * an error. In that case, a nonzero value is returned (1).
+ * an error. In that case, a nonzero value is returned (EXIT_FAILURE=1).
*
****************************************************************************/
-EXTERN int nsh_consolemain(int argc, char *argv[]);
+int nsh_consolemain(int argc, char *argv[]);
-/* nsh_telnetstart() starts a telnet daemon that will allow multiple
- * NSH connections via telnet. This function returns immediately after
- * the daemon has been started.
- */
+/****************************************************************************
+ * Name: nsh_telnetstart
+ *
+ * Description:
+ * nsh_telnetstart() starts the Telnet daemon that will allow multiple
+ * NSH connections via Telnet. This function returns immediately after
+ * the daemon has been started.
+ *
+ * Input Parameters:
+ * None. All of the properties of the Telnet daemon are controlled by
+ * NuttX configuration setting.
+ *
+ * Returned Values:
+ * The task ID of the Telnet daemon was successfully started. A negated
+ * errno value will be returned on failure.
+ *
+ ****************************************************************************/
-EXTERN int nsh_telnetstart(void);
+int nsh_telnetstart(void);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/sched/env_dupenv.c b/apps/include/usbmonitor.h
index 32bf6a433..01fa060b0 100644
--- a/nuttx/sched/env_dupenv.c
+++ b/apps/include/usbmonitor.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * eched/env_dupenv.c
+ * apps/include/usbmonitor.h
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,80 +33,64 @@
*
****************************************************************************/
+#ifndef __APPS_INCLUDE_USBMONITOR_H
+#define __APPS_INCLUDE_USBMONITOR_H
+
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
-#ifndef CONFIG_DISABLE_ENVIRON
-
-#include <sys/types.h>
-#include <sched.h>
-
-#include <nuttx/kmalloc.h>
+#ifdef CONFIG_SYSTEM_USBMONITOR
-#include "os_internal.h"
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
/****************************************************************************
- * Private Data
+ * Public Data
****************************************************************************/
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
/****************************************************************************
- * Public Functions
+ * Public Function Prototypes
****************************************************************************/
/****************************************************************************
- * Name: dupenv
+ * Name: usbmon_start and usbmon_stop
*
- * Description:
- * Copy the internal environment structure of a task. This is the action
- * that is performed when a new task is created: The new task has a private,
- * exact duplicate of the parent task's environment.
+ * Start and top the USB monitor daemon. These are normally controlled
+ * from the USB command line, but the ability to control these
+ * programmatically is also helpful (for example, so that the daemon is
+ * running before NSH starts).
*
- * Parameters:
- * None
+ * Input Parameters:
+ * Standard task parameters. These can be called or spawned. Since the
+ * return almost immediately, it is fine to just call the functions. The
+ * parameters are not used so you can pass 0 and NULL, respectivley; this
+ * is done this way so that these functions can be NSH builtin
+ * applications.
*
- * Return Value:
- * A pointer to a newly allocated copy of the specified TCB's environment
- * structure with reference count equal to one.
+ * Returned values:
+ * Standard task return values (zero meaning success).
*
- * Assumptions:
- * Not called from an interrupt handler.
- *
- ****************************************************************************/
+ **************************************************************************/
-FAR environ_t *dupenv(FAR _TCB *ptcb)
-{
- environ_t *envp = NULL;
-
- /* Pre-emption must be disabled throughout the following because the
- * environment may be shared.
- */
-
- sched_lock();
-
- /* Does the parent task have an environment? */
-
- if (ptcb->envp)
- {
- /* Yes..The parent task has an environment, duplicate it */
+int usbmonitor_start(int argc, char **argv);
+int usbmonitor_stop(int argc, char **argv);
- size_t envlen = ptcb->envp->ev_alloc
- envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen ));
- if (envp)
- {
- envp->ev_crefs = 1;
- envp->ev_alloc = envlen;
- memcmp( envp->ev_env, ptcb->envp->ev_env, envlen );
- }
- }
-
- sched_unlock();
- return envp;
+#undef EXTERN
+#ifdef __cplusplus
}
+#endif
-#endif /* CONFIG_DISABLE_ENVIRON */
-
-
-
+#endif /* CONFIG_SYSTEM_USBMONITOR */
+#endif /* __APPS_INCLUDE_USBMONITOR_H */
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index ceb7c2554..b958d5f96 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -625,7 +625,9 @@ int mavlink_thread_main(int argc, char *argv[])
/* 20 Hz / 50 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 10);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 50);
- /* 2 Hz */
+ /* 10 Hz */
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW_INT, 100);
+ /* 10 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 100);
} else if (baudrate >= 115200) {
@@ -634,8 +636,10 @@ int mavlink_thread_main(int argc, char *argv[])
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 50);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 50);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 50);
- /* 5 Hz / 100 ms */
+ /* 5 Hz / 200 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 200);
+ /* 5 Hz / 200 ms */
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW_INT, 200);
/* 2 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500);
@@ -651,6 +655,8 @@ int mavlink_thread_main(int argc, char *argv[])
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 500);
/* 2 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500);
+ /* 2 Hz */
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_GPS_RAW_INT, 500);
} else {
/* very low baud rate, limit to 1 Hz / 1000 ms */
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 510d2f3e4..4d9cd964d 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -387,22 +387,22 @@ handle_message(mavlink_message_t *msg)
static uint64_t old_timestamp = 0;
/* gps */
- hil_gps.timestamp = gps.time_usec;
- hil_gps.counter = hil_counter++;
+ hil_gps.timestamp_position = gps.time_usec;
+// hil_gps.counter = hil_counter++;
hil_gps.time_gps_usec = gps.time_usec;
hil_gps.lat = gps.lat;
hil_gps.lon = gps.lon;
hil_gps.alt = gps.alt;
- hil_gps.counter_pos_valid = hil_counter++;
- hil_gps.eph = gps.eph;
- hil_gps.epv = gps.epv;
- hil_gps.s_variance = 100;
- hil_gps.p_variance = 100;
- hil_gps.vel = gps.vel;
- hil_gps.vel_n = gps.vel / 100.0f * cosf(gps.cog / M_RAD_TO_DEG_F / 100.0f);
- hil_gps.vel_e = gps.vel / 100.0f * sinf(gps.cog / M_RAD_TO_DEG_F / 100.0f);
- hil_gps.vel_d = 0.0f;
- hil_gps.cog = gps.cog;
+// hil_gps.counter_pos_valid = hil_counter++;
+ hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
+ hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
+ hil_gps.s_variance_m_s = 100; // XXX 100 m/s variance?
+ hil_gps.p_variance_m = 100; // XXX 100 m variance?
+ hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
+ hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
+ hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
+ hil_gps.vel_d_m_s = 0.0f;
+ hil_gps.cog_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; // from deg*100 to rad
hil_gps.fix_type = gps.fix_type;
hil_gps.satellites_visible = gps.satellites_visible;
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index ec5149745..9f85d5801 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -231,15 +231,15 @@ l_vehicle_gps_position(struct listener *l)
/* GPS position */
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
- gps.timestamp,
+ gps.timestamp_position,
gps.fix_type,
gps.lat,
gps.lon,
gps.alt,
- gps.eph,
- gps.epv,
- gps.vel,
- gps.cog,
+ (uint16_t)(gps.eph_m * 1e2f), // from m to cm
+ (uint16_t)(gps.epv_m * 1e2f), // from m to cm
+ (uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s
+ (uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100
gps.satellites_visible);
if (gps.satellite_info_available && (gps_counter % 4 == 0)) {
@@ -698,7 +698,7 @@ uorb_receive_start(void)
/* --- GPS VALUE --- */
mavlink_subs.gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- orb_set_interval(mavlink_subs.gps_sub, 1000); /* 1Hz updates */
+ orb_set_interval(mavlink_subs.gps_sub, 200); /* 5Hz updates */
/* --- HOME POSITION --- */
mavlink_subs.home_sub = orb_subscribe(ORB_ID(home_position));
diff --git a/apps/nshlib/Kconfig b/apps/nshlib/Kconfig
index f6a5aa045..92bc83cfd 100644
--- a/apps/nshlib/Kconfig
+++ b/apps/nshlib/Kconfig
@@ -292,6 +292,19 @@ config NSH_ROMFSETC
endif
if NSH_ROMFSETC
+
+config NSH_ROMFSRC
+ bool "Support ROMFS login script"
+ default n
+ ---help---
+ The ROMFS start-up script will be executed excactly once. For
+ simple, persistence consoles (like a serial console). But with
+ other other kinds of consoles, there may be multiple, transient
+ sessions (such as Telnet and USB consoles). In these cases, you
+ may need another script that is executed at the beginning of each
+ session. Selecting this option enables support for such a login
+ script
+
config NSH_ROMFSMOUNTPT
string "ROMFS mount point"
default "/etc"
@@ -308,6 +321,15 @@ config NSH_INITSCRIPT
The default is init.d/rcS. This is a relative path and must not
start with '/'.
+config NSH_RCSCRIPT
+ string "Relative path to login script"
+ default ".nshrc"
+ depends on NSH_ROMFSRC
+ ---help---
+ This is the relative path to the login script within the mountpoint.
+ The default is .nshrc. This is a relative path and must not
+ start with '/'.
+
config NSH_ROMFSDEVNO
int "ROMFS block device minor number"
default 0
@@ -406,7 +428,7 @@ config NSH_USBCONDEV
readable/write-able USB driver such as:
NSH_USBCONDEV="/dev/ttyACM0".
-config UBSDEV_MINOR
+config USBDEV_MINOR
int "USB console device minor number"
default 0
depends on NSH_USBCONSOLE
@@ -414,8 +436,22 @@ config UBSDEV_MINOR
If there are more than one USB devices, then a USB device
minor number may also need to be provided. Default: 0
-menu "USB Trace Support"
+comment "USB Trace Support"
+config NSH_USBDEV_TRACE
+ bool "Enable Builtin USB Trace Support"
+ default n
depends on USBDEV && (DEBUG || USBDEV_TRACE)
+ ---help---
+ Enable builtin USB trace support in NSH. If selected, buffered USB
+ trace data will be presented each time a command is provided to NSH.
+ The USB trace data will be sent to the console unless DEBUG set or
+ unless you are using a USB console. In those cases, the trace data
+ will go to the SYSLOG device.
+
+ If not enabled, the USB trace support can be provided by external
+ logic such as apps/system/usbmonitor.
+
+if NSH_USBDEV_TRACE
config NSH_USBDEV_TRACEINIT
bool "Show initialization events"
@@ -447,7 +483,7 @@ config NSH_USBDEV_TRACEINTERRUPTS
---help---
Show interrupt-related events
-endmenu
+endif
config NSH_CONDEV
bool "Default console device"
diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
index 948f43d52..76cdac40d 100644
--- a/apps/nshlib/Makefile
+++ b/apps/nshlib/Makefile
@@ -1,7 +1,7 @@
############################################################################
# apps/nshlib/Makefile
#
-# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -39,9 +39,10 @@ include $(APPDIR)/Make.defs
# NSH Library
-ASRCS =
-CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_fscmds.c nsh_ddcmd.c \
- nsh_proccmds.c nsh_mmcmds.c nsh_envcmds.c nsh_dbgcmds.c
+ASRCS =
+CSRCS = nsh_init.c nsh_parse.c nsh_console.c nsh_script.c nsh_session.c
+CSRCS += nsh_fscmds.c nsh_ddcmd.c nsh_proccmds.c nsh_mmcmds.c nsh_envcmds.c
+CSRCS += nsh_dbgcmds.c
ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
CSRCS += nsh_builtin.c
diff --git a/apps/nshlib/README.txt b/apps/nshlib/README.txt
index 006839628..a03f4a8ee 100644
--- a/apps/nshlib/README.txt
+++ b/apps/nshlib/README.txt
@@ -1025,12 +1025,16 @@ NSH-Specific Configuration Settings
If there are more than one USB devices, then a USB device
minor number may also need to be provided:
- CONFIG_NSH_UBSDEV_MINOR
+ CONFIG_NSH_USBDEV_MINOR
The minor device number of the USB device. Default: 0
- If USB tracing is enabled (CONFIG_USBDEV_TRACE), then NSH will
- initialize USB tracing as requested by the following. Default:
- Only USB errors are traced.
+ CONFIG_NSH_USBDEV_TRACE
+ If USB tracing is enabled (CONFIG_USBDEV_TRACE), then NSH can
+ be configured to show the buffered USB trace data afer each
+ NSH command:
+
+ If CONFIG_NSH_USBDEV_TRACE is selected, then USB trace data
+ can be filtered as follows. Default: Only USB errors are traced.
CONFIG_NSH_USBDEV_TRACEINIT
Show initialization events
diff --git a/apps/nshlib/nsh.h b/apps/nshlib/nsh.h
index 64099a8df..23209dba5 100644
--- a/apps/nshlib/nsh.h
+++ b/apps/nshlib/nsh.h
@@ -1,7 +1,7 @@
/****************************************************************************
* apps/nshlib/nsh.h
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -93,7 +93,9 @@
# elif defined(CONFIG_CDCACM) && defined(CONFIG_CDCACM_CONSOLE)
# define HAVE_USB_CONSOLE 1
-/* Check for other USB console. USB console device must be provided in CONFIG_NSH_CONDEV */
+/* Check for a generic USB console. In this case, the USB console device
+ * must be provided in CONFIG_NSH_CONDEV.
+ */
# elif defined(CONFIG_NSH_USBCONSOLE)
# define HAVE_USB_CONSOLE 1
@@ -106,8 +108,8 @@
/* The default USB console device minor number is 0*/
-# ifndef CONFIG_NSH_UBSDEV_MINOR
-# define CONFIG_NSH_UBSDEV_MINOR 0
+# ifndef CONFIG_NSH_USBDEV_MINOR
+# define CONFIG_NSH_USBDEV_MINOR 0
# endif
/* The default console device is always /dev/console */
@@ -118,43 +120,53 @@
/* USB trace settings */
-#ifdef CONFIG_NSH_USBDEV_TRACEINIT
-# define TRACE_INIT_BITS (TRACE_INIT_BIT)
-#else
-# define TRACE_INIT_BITS (0)
-#endif
+# ifndef CONFIG_USBDEV_TRACE
+# undef CONFIG_NSH_USBDEV_TRACE
+# endif
-#define TRACE_ERROR_BITS (TRACE_DEVERROR_BIT|TRACE_CLSERROR_BIT)
+# ifdef CONFIG_NSH_USBDEV_TRACE
+# ifdef CONFIG_NSH_USBDEV_TRACEINIT
+# define TRACE_INIT_BITS (TRACE_INIT_BIT)
+# else
+# define TRACE_INIT_BITS (0)
+# endif
-#ifdef CONFIG_NSH_USBDEV_TRACECLASS
-# define TRACE_CLASS_BITS (TRACE_CLASS_BIT|TRACE_CLASSAPI_BIT|TRACE_CLASSSTATE_BIT)
-#else
-# define TRACE_CLASS_BITS (0)
-#endif
+# define TRACE_ERROR_BITS (TRACE_DEVERROR_BIT|TRACE_CLSERROR_BIT)
-#ifdef CONFIG_NSH_USBDEV_TRACETRANSFERS
-# define TRACE_TRANSFER_BITS (TRACE_OUTREQQUEUED_BIT|TRACE_INREQQUEUED_BIT|TRACE_READ_BIT|\
- TRACE_WRITE_BIT|TRACE_COMPLETE_BIT)
-#else
-# define TRACE_TRANSFER_BITS (0)
-#endif
+# ifdef CONFIG_NSH_USBDEV_TRACECLASS
+# define TRACE_CLASS_BITS (TRACE_CLASS_BIT|TRACE_CLASSAPI_BIT|\
+ TRACE_CLASSSTATE_BIT)
+# else
+# define TRACE_CLASS_BITS (0)
+# endif
-#ifdef CONFIG_NSH_USBDEV_TRACECONTROLLER
-# define TRACE_CONTROLLER_BITS (TRACE_EP_BIT|TRACE_DEV_BIT)
-#else
-# define TRACE_CONTROLLER_BITS (0)
-#endif
+# ifdef CONFIG_NSH_USBDEV_TRACETRANSFERS
+# define TRACE_TRANSFER_BITS (TRACE_OUTREQQUEUED_BIT|TRACE_INREQQUEUED_BIT|\
+ TRACE_READ_BIT|TRACE_WRITE_BIT|\
+ TRACE_COMPLETE_BIT)
+# else
+# define TRACE_TRANSFER_BITS (0)
+# endif
-#ifdef CONFIG_NSH_USBDEV_TRACEINTERRUPTS
-# define TRACE_INTERRUPT_BITS (TRACE_INTENTRY_BIT|TRACE_INTDECODE_BIT|TRACE_INTEXIT_BIT)
-#else
-# define TRACE_INTERRUPT_BITS (0)
-#endif
+# ifdef CONFIG_NSH_USBDEV_TRACECONTROLLER
+# define TRACE_CONTROLLER_BITS (TRACE_EP_BIT|TRACE_DEV_BIT)
+# else
+# define TRACE_CONTROLLER_BITS (0)
+# endif
-#define TRACE_BITSET (TRACE_INIT_BITS|TRACE_ERROR_BITS|TRACE_CLASS_BITS|\
- TRACE_TRANSFER_BITS|TRACE_CONTROLLER_BITS|TRACE_INTERRUPT_BITS)
+# ifdef CONFIG_NSH_USBDEV_TRACEINTERRUPTS
+# define TRACE_INTERRUPT_BITS (TRACE_INTENTRY_BIT|TRACE_INTDECODE_BIT|\
+ TRACE_INTEXIT_BIT)
+# else
+# define TRACE_INTERRUPT_BITS (0)
+# endif
-#endif
+# define TRACE_BITSET (TRACE_INIT_BITS|TRACE_ERROR_BITS|\
+ TRACE_CLASS_BITS|TRACE_TRANSFER_BITS|\
+ TRACE_CONTROLLER_BITS|TRACE_INTERRUPT_BITS)
+
+# endif /* CONFIG_NSH_USBDEV_TRACE */
+#endif /* HAVE_USB_CONSOLE */
/* If Telnet is selected for the NSH console, then we must configure
* the resources used by the Telnet daemon and by the Telnet clients.
@@ -232,40 +244,59 @@
# error "Mountpoint support is disabled"
# undef CONFIG_NSH_ROMFSETC
# endif
+
# if CONFIG_NFILE_DESCRIPTORS < 4
# error "Not enough file descriptors"
# undef CONFIG_NSH_ROMFSETC
# endif
+
# ifndef CONFIG_FS_ROMFS
# error "ROMFS support not enabled"
# undef CONFIG_NSH_ROMFSETC
# endif
+
# ifndef CONFIG_NSH_ROMFSMOUNTPT
# define CONFIG_NSH_ROMFSMOUNTPT "/etc"
# endif
-# ifdef CONFIG_NSH_INIT
-# ifndef CONFIG_NSH_INITSCRIPT
-# define CONFIG_NSH_INITSCRIPT "init.d/rcS"
-# endif
+
+# ifndef CONFIG_NSH_INITSCRIPT
+# define CONFIG_NSH_INITSCRIPT "init.d/rcS"
# endif
+
# undef NSH_INITPATH
# define NSH_INITPATH CONFIG_NSH_ROMFSMOUNTPT "/" CONFIG_NSH_INITSCRIPT
+
+# ifdef CONFIG_NSH_ROMFSRC
+# ifndef CONFIG_NSH_RCSCRIPT
+# define CONFIG_NSH_RCSCRIPT ".nshrc"
+# endif
+
+# undef NSH_RCPATH
+# define NSH_RCPATH CONFIG_NSH_ROMFSMOUNTPT "/" CONFIG_NSH_RCSCRIPT
+# endif
+
# ifndef CONFIG_NSH_ROMFSDEVNO
# define CONFIG_NSH_ROMFSDEVNO 0
# endif
+
# ifndef CONFIG_NSH_ROMFSSECTSIZE
# define CONFIG_NSH_ROMFSSECTSIZE 64
# endif
+
# define NSECTORS(b) (((b)+CONFIG_NSH_ROMFSSECTSIZE-1)/CONFIG_NSH_ROMFSSECTSIZE)
# define STR_RAMDEVNO(m) #m
# define MKMOUNT_DEVNAME(m) "/dev/ram" STR_RAMDEVNO(m)
# define MOUNT_DEVNAME MKMOUNT_DEVNAME(CONFIG_NSH_ROMFSDEVNO)
+
#else
+
+# undef CONFIG_NSH_ROMFSRC
# undef CONFIG_NSH_ROMFSMOUNTPT
-# undef CONFIG_NSH_INIT
# undef CONFIG_NSH_INITSCRIPT
+# undef CONFIG_NSH_RCSCRIPT
# undef CONFIG_NSH_ROMFSDEVNO
# undef CONFIG_NSH_ROMFSSECTSIZE
+
#endif
/* This is the maximum number of arguments that will be accepted for a
@@ -474,6 +505,12 @@ int nsh_usbconsole(void);
#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0 && !defined(CONFIG_NSH_DISABLESCRIPT)
int nsh_script(FAR struct nsh_vtbl_s *vtbl, const char *cmd, const char *path);
+#ifdef CONFIG_NSH_ROMFSETC
+int nsh_initscript(FAR struct nsh_vtbl_s *vtbl);
+#ifdef CONFIG_NSH_ROMFSRC
+int nsh_loginscript(FAR struct nsh_vtbl_s *vtbl);
+#endif
+#endif
#endif
/* Architecture-specific initialization */
@@ -484,8 +521,10 @@ int nsh_archinitialize(void);
# define nsh_archinitialize() (-ENOSYS)
#endif
-/* Message handler */
+/* Basic session and message handling */
+struct console_stdio_s;
+int nsh_session(FAR struct console_stdio_s *pstate);
int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline);
/* Application interface */
@@ -515,10 +554,8 @@ void nsh_dumpbuffer(FAR struct nsh_vtbl_s *vtbl, const char *msg,
/* USB debug support */
-#if defined(CONFIG_USBDEV_TRACE) && defined(HAVE_USB_CONSOLE)
+#ifdef CONFIG_NSH_USBDEV_TRACE
void nsh_usbtrace(void);
-#else
-# define nsh_usbtrace()
#endif
/* Shell command handlers */
diff --git a/apps/nshlib/nsh_consolemain.c b/apps/nshlib/nsh_consolemain.c
index f05447a64..8be44f7aa 100644
--- a/apps/nshlib/nsh_consolemain.c
+++ b/apps/nshlib/nsh_consolemain.c
@@ -1,7 +1,7 @@
/****************************************************************************
* apps/nshlib/nsh_consolemain.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,8 @@
#include "nsh.h"
#include "nsh_console.h"
+#ifndef HAVE_USB_CONSOLE
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -76,21 +78,25 @@
****************************************************************************/
/****************************************************************************
- * Name: nsh_consolemain
+ * Name: nsh_consolemain (Normal character device version)
*
* Description:
* This interfaces maybe to called or started with task_start to start a
- * single an NSH instance that operates on stdin and stdout (/dev/console).
- * This function does not return.
+ * single an NSH instance that operates on stdin and stdout. This
+ * function does not normally return (see below).
*
+ * This version of nsh_consolmain handles generic /dev/console character
+ * devices (see nsh_usbdev.c for another version for special USB console
+ * devices).
+ *
* Input Parameters:
- * Standard task start-up arguements. These are not used. argc may be
+ * Standard task start-up arguments. These are not used. argc may be
* zero and argv may be NULL.
*
* Returned Values:
* This function does not normally return. exit() is usually called to
* terminate the NSH session. This function will return in the event of
- * an error. In that case, a nonzero value is returned (1).
+ * an error. In that case, a nonzero value is returned (EXIT_FAILURE=1).
*
****************************************************************************/
@@ -101,70 +107,26 @@ int nsh_consolemain(int argc, char *argv[])
DEBUGASSERT(pstate);
- /* If we are using a USB serial console, then we will have to wait for the
- * USB to be connected to the host.
- */
-
-#ifdef HAVE_USB_CONSOLE
- ret = nsh_usbconsole();
- DEBUGASSERT(ret == OK);
-#endif
-
- /* Present a greeting */
-
- fputs(g_nshgreeting, pstate->cn_outstream);
- fflush(pstate->cn_outstream);
-
- /* Execute the startup script */
+ /* Execute the start-up script */
#ifdef CONFIG_NSH_ROMFSETC
- (void)nsh_script(&pstate->cn_vtbl, "init", NSH_INITPATH);
+ (void)nsh_initscript(&pstate->cn_vtbl);
#endif
- /* Then enter the command line parsing loop */
-
- for (;;)
- {
- /* For the case of debugging the USB console... dump collected USB trace data */
+ /* Initialize any USB tracing options that were requested */
- nsh_usbtrace();
-
- /* Display the prompt string */
-
- fputs(g_nshprompt, pstate->cn_outstream);
- fflush(pstate->cn_outstream);
-
- /* Get the next line of input */
-
- ret = readline(pstate->cn_line, CONFIG_NSH_LINELEN,
- INSTREAM(pstate), OUTSTREAM(pstate));
- if (ret > 0)
- {
- /* Parse process the command */
-
- (void)nsh_parse(&pstate->cn_vtbl, pstate->cn_line);
- fflush(pstate->cn_outstream);
- }
+#ifdef CONFIG_NSH_USBDEV_TRACE
+ usbtrace_enable(TRACE_BITSET);
+#endif
- /* Readline normally returns the number of characters read,
- * but will return 0 on end of file or a negative value
- * if an error occurs. Either will cause the session to
- * terminate.
- */
+ /* Execute the session */
- else
- {
- fprintf(pstate->cn_outstream, g_fmtcmdfailed, "nsh_consolemain",
- "readline", NSH_ERRNO_OF(-ret));
- nsh_exit(&pstate->cn_vtbl, 1);
- }
- }
+ ret = nsh_session(pstate);
- /* Clean up. We do not get here, but this is necessary to keep some
- * compilers happy. But others will complain that this code is not
- * reachable.
- */
+ /* Exit upon return */
- nsh_exit(&pstate->cn_vtbl, 0);
- return OK;
+ nsh_exit(&pstate->cn_vtbl, ret);
+ return ret;
}
+
+#endif /* !HAVE_USB_CONSOLE */
diff --git a/apps/nshlib/nsh_ddcmd.c b/apps/nshlib/nsh_ddcmd.c
index 40a3710b1..e6ef2523c 100644
--- a/apps/nshlib/nsh_ddcmd.c
+++ b/apps/nshlib/nsh_ddcmd.c
@@ -545,7 +545,7 @@ int cmd_dd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
}
#endif
- if (dd.skip < 0 || dd.skip > dd.nsectors)
+ if (dd.skip > dd.nsectors)
{
nsh_output(vtbl, g_fmtarginvalid, g_dd);
goto errout_with_paths;
diff --git a/apps/nshlib/nsh_fscmds.c b/apps/nshlib/nsh_fscmds.c
index 1a9f2eb57..f47dca896 100644
--- a/apps/nshlib/nsh_fscmds.c
+++ b/apps/nshlib/nsh_fscmds.c
@@ -1,7 +1,7 @@
/****************************************************************************
* apps/nshlib/nsh_fscmds.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -1221,71 +1221,6 @@ int cmd_rmdir(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
#endif
/****************************************************************************
- * Name: nsh_script
- ****************************************************************************/
-
-#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0 && !defined(CONFIG_NSH_DISABLESCRIPT)
-int nsh_script(FAR struct nsh_vtbl_s *vtbl, const char *cmd, const char *path)
-{
- char *fullpath;
- FILE *stream;
- char *buffer;
- char *pret;
- int ret = ERROR;
-
- /* The path to the script may be relative to the current working directory */
-
- fullpath = nsh_getfullpath(vtbl, path);
- if (!fullpath)
- {
- return ERROR;
- }
-
- /* Get a reference to the common input buffer */
-
- buffer = nsh_linebuffer(vtbl);
- if (buffer)
- {
- /* Open the file containing the script */
-
- stream = fopen(fullpath, "r");
- if (!stream)
- {
- nsh_output(vtbl, g_fmtcmdfailed, cmd, "fopen", NSH_ERRNO);
- nsh_freefullpath(fullpath);
- return ERROR;
- }
-
- /* Loop, processing each command line in the script file (or
- * until an error occurs)
- */
-
- do
- {
- /* Get the next line of input from the file */
-
- fflush(stdout);
- pret = fgets(buffer, CONFIG_NSH_LINELEN, stream);
- if (pret)
- {
- /* Parse process the command. NOTE: this is recursive...
- * we got to cmd_sh via a call to nsh_parse. So some
- * considerable amount of stack may be used.
- */
-
- ret = nsh_parse(vtbl, buffer);
- }
- }
- while (pret && ret == OK);
- fclose(stream);
- }
-
- nsh_freefullpath(fullpath);
- return ret;
-}
-#endif
-
-/****************************************************************************
* Name: cmd_sh
****************************************************************************/
diff --git a/apps/nshlib/nsh_script.c b/apps/nshlib/nsh_script.c
new file mode 100644
index 000000000..3aa698b31
--- /dev/null
+++ b/apps/nshlib/nsh_script.c
@@ -0,0 +1,195 @@
+/****************************************************************************
+ * apps/nshlib/nsh_script.c
+ *
+ * Copyright (C) 2007-2009, 2011-2013 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 "nsh.h"
+#include "nsh_console.h"
+
+#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0 && !defined(CONFIG_NSH_DISABLESCRIPT)
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_script
+ *
+ * Description:
+ * Execute the NSH script at path.
+ *
+ ****************************************************************************/
+
+int nsh_script(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
+ FAR const char *path)
+{
+ char *fullpath;
+ FILE *stream;
+ char *buffer;
+ char *pret;
+ int ret = ERROR;
+
+ /* The path to the script may be relative to the current working directory */
+
+ fullpath = nsh_getfullpath(vtbl, path);
+ if (!fullpath)
+ {
+ return ERROR;
+ }
+
+ /* Get a reference to the common input buffer */
+
+ buffer = nsh_linebuffer(vtbl);
+ if (buffer)
+ {
+ /* Open the file containing the script */
+
+ stream = fopen(fullpath, "r");
+ if (!stream)
+ {
+ nsh_output(vtbl, g_fmtcmdfailed, cmd, "fopen", NSH_ERRNO);
+ nsh_freefullpath(fullpath);
+ return ERROR;
+ }
+
+ /* Loop, processing each command line in the script file (or
+ * until an error occurs)
+ */
+
+ do
+ {
+ /* Get the next line of input from the file */
+
+ fflush(stdout);
+ pret = fgets(buffer, CONFIG_NSH_LINELEN, stream);
+ if (pret)
+ {
+ /* Parse process the command. NOTE: this is recursive...
+ * we got to cmd_sh via a call to nsh_parse. So some
+ * considerable amount of stack may be used.
+ */
+
+ ret = nsh_parse(vtbl, buffer);
+ }
+ }
+ while (pret && ret == OK);
+ fclose(stream);
+ }
+
+ nsh_freefullpath(fullpath);
+ return ret;
+}
+
+/****************************************************************************
+ * Name: nsh_initscript
+ *
+ * Description:
+ * Attempt to execute the configured initialization script. This script
+ * should be executed once when NSH starts. nsh_initscript is idempotent
+ * and may, however, be called multiple times (the script will be executed
+ * once.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_ROMFSETC
+int nsh_initscript(FAR struct nsh_vtbl_s *vtbl)
+{
+ static bool initialized;
+ bool already;
+ int ret = OK;
+
+ /* Atomic test and set of the initialized flag */
+
+ sched_lock();
+ already = initialized;
+ initialized = true;
+ sched_unlock();
+
+ /* If we have not already executed the init script, then do so now */
+
+ if (!already)
+ {
+ ret = nsh_script(vtbl, "init", NSH_INITPATH);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: nsh_loginscript
+ *
+ * Description:
+ * Attempt to execute the configured login script. This script
+ * should be executed when each NSH session starts.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_ROMFSRC
+int nsh_loginscript(FAR struct nsh_vtbl_s *vtbl)
+{
+ return nsh_script(vtbl, "login", NSH_RCPATH);
+}
+#endif
+#endif /* CONFIG_NSH_ROMFSETC */
+
+#endif /* CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0 && !CONFIG_NSH_DISABLESCRIPT */
diff --git a/apps/nshlib/nsh_session.c b/apps/nshlib/nsh_session.c
new file mode 100644
index 000000000..8079b2de5
--- /dev/null
+++ b/apps/nshlib/nsh_session.c
@@ -0,0 +1,163 @@
+/****************************************************************************
+ * apps/nshlib/nsh_session.c
+ *
+ * Copyright (C) 2007-2009, 2011-2013 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 Gregory Nutt 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 <stdio.h>
+#include <stdlib.h>
+
+#include <apps/readline.h>
+
+#include "nsh.h"
+#include "nsh_console.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_session
+ *
+ * Description:
+ * This is the common session logic or any NSH session. This function
+ * return when an error reading from the input stream occurs, presumably
+ * signaling the end of the session.
+ *
+ * This function:
+ * - Executes the NSH logic script
+ * - Presents a greeting
+ * - Then provides a prompt then gets and processes the command line.
+ * - This continues until an error occurs, then the session returns.
+ *
+ * Input Parameters:
+ * pstate - Abstracts the underlying session.
+ *
+ * Returned Values:
+ * EXIT_SUCESS or EXIT_FAILURE is returned.
+ *
+ ****************************************************************************/
+
+int nsh_session(FAR struct console_stdio_s *pstate)
+{
+ int ret;
+
+ DEBUGASSERT(pstate);
+
+ /* Present a greeting */
+
+ fputs(g_nshgreeting, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+
+ /* Execute the login script */
+
+#ifdef CONFIG_NSH_ROMFSRC
+ (void)nsh_loginscript(&pstate->cn_vtbl);
+#endif
+
+ /* Then enter the command line parsing loop */
+
+ for (;;)
+ {
+ /* For the case of debugging the USB console... dump collected USB trace data */
+
+#ifdef CONFIG_NSH_USBDEV_TRACE
+ nsh_usbtrace();
+#endif
+
+ /* Display the prompt string */
+
+ fputs(g_nshprompt, pstate->cn_outstream);
+ fflush(pstate->cn_outstream);
+
+ /* Get the next line of input */
+
+ ret = readline(pstate->cn_line, CONFIG_NSH_LINELEN,
+ INSTREAM(pstate), OUTSTREAM(pstate));
+ if (ret > 0)
+ {
+ /* Parse process the command */
+
+ (void)nsh_parse(&pstate->cn_vtbl, pstate->cn_line);
+ fflush(pstate->cn_outstream);
+ }
+
+ /* Readline normally returns the number of characters read,
+ * but will return 0 on end of file or a negative value
+ * if an error occurs. Either will cause the session to
+ * terminate.
+ */
+
+ else
+ {
+ fprintf(pstate->cn_outstream, g_fmtcmdfailed, "nsh_session",
+ "readline", NSH_ERRNO_OF(-ret));
+ return ret == 0 ? EXIT_SUCCESS : EXIT_FAILURE;
+ }
+ }
+
+ /* We do not get here, but this is necessary to keep some compilers happy.
+ * But others will complain that this code is not reachable.
+ */
+
+ return EXIT_SUCCESS;
+}
diff --git a/apps/nshlib/nsh_telnetd.c b/apps/nshlib/nsh_telnetd.c
index 478935d7f..76ed81086 100644
--- a/apps/nshlib/nsh_telnetd.c
+++ b/apps/nshlib/nsh_telnetd.c
@@ -1,7 +1,7 @@
/****************************************************************************
* apps/nshlib/nsh_telnetd.c
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -198,15 +198,29 @@ int nsh_telnetmain(int argc, char *argv[])
}
#endif /* CONFIG_NSH_TELNET_LOGIN */
+ /* The following logic mostly the same as the login in nsh_session.c. It
+ * differs only in that gets() is called to get the command instead of
+ * readline().
+ */
+
/* Present the NSH greeting */
fputs(g_nshgreeting, pstate->cn_outstream);
fflush(pstate->cn_outstream);
- /* Execute the startup script */
+ /* Execute the startup script. If standard console is also defined, then
+ * we will not bother with the initscript here (although it is safe to
+ * call nshinitscript multiple times).
+ */
#if defined(CONFIG_NSH_ROMFSETC) && !defined(CONFIG_NSH_CONSOLE)
- (void)nsh_script(&pstate->cn_vtbl, "init", NSH_INITPATH);
+ (void)nsh_initscript(&pstate->cn_vtbl);
+#endif
+
+ /* Execute the login script */
+
+#ifdef CONFIG_NSH_ROMFSRC
+ (void)nsh_loginscript(&pstate->cn_vtbl);
#endif
/* Then enter the command line parsing loop */
@@ -261,8 +275,8 @@ int nsh_telnetmain(int argc, char *argv[])
* NuttX configuration setting.
*
* Returned Values:
- * Zero if the Telnet daemon was successfully started. A negated errno
- * value will be returned on failure.
+ * The task ID of the Telnet daemon was successfully started. A negated
+ * errno value will be returned on failure.
*
****************************************************************************/
@@ -271,6 +285,15 @@ int nsh_telnetstart(void)
struct telnetd_config_s config;
int ret;
+ /* Initialize any USB tracing options that were requested. If standard
+ * console is also defined, then we will defer this step to the standard
+ * console.
+ */
+
+#if defined(CONFIG_NSH_USBDEV_TRACE) && !defined(CONFIG_NSH_CONSOLE)
+ usbtrace_enable(TRACE_BITSET);
+#endif
+
/* Configure the telnet daemon */
config.d_port = HTONS(CONFIG_NSH_TELNETD_PORT);
diff --git a/apps/nshlib/nsh_usbdev.c b/apps/nshlib/nsh_usbdev.c
index 3d123532a..193fe0d79 100644
--- a/apps/nshlib/nsh_usbdev.c
+++ b/apps/nshlib/nsh_usbdev.c
@@ -1,7 +1,7 @@
/****************************************************************************
* apps/nshlib/nsh_usbdev.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,15 +55,20 @@
#endif
#include "nsh.h"
-
-#ifdef CONFIG_USBDEV
+#include "nsh_console.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
-
-#if defined(CONFIG_DEBUG) || defined(CONFIG_NSH_USBCONSOLE)
-# define trmessage lib_lowprintf
+/* Output USB trace data to the console device using printf() unless (1)
+ * debug is enabled, then we want to keep the trace output in sync with the
+ * debug output by using syslog()we are using a USB console. In that case,
+ * we don't want the trace output on the USB console; let's try sending it
+ * a SYSLOG device (hopefully one is set up!)
+ */
+
+#if defined(CONFIG_DEBUG) || defined(HAVE_USB_CONSOLE)
+# define trmessage syslog
#else
# define trmessage printf
#endif
@@ -92,7 +97,15 @@
* Name: nsh_tracecallback
****************************************************************************/
-#ifdef CONFIG_USBDEV_TRACE
+/****************************************************************************
+ * Name: nsh_tracecallback
+ *
+ * Description:
+ * This is part of the USB trace logic
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_USBDEV_TRACE
static int nsh_tracecallback(struct usbtrace_s *trace, void *arg)
{
usbtrace_trprintf((trprintf_t)trmessage, trace->event, trace->value);
@@ -101,45 +114,103 @@ static int nsh_tracecallback(struct usbtrace_s *trace, void *arg)
#endif
/****************************************************************************
- * Public Functions
+ * Name: nsh_configstdio
+ *
+ * Description:
+ * Configure standard I/O
+ *
****************************************************************************/
+#ifdef HAVE_USB_CONSOLE
+static void nsh_configstdio(int fd)
+{
+ /* Make sure the stdin, stdout, and stderr are closed */
+
+ (void)fclose(stdin);
+ (void)fclose(stdout);
+ (void)fclose(stderr);
+
+ /* Dup the fd to create standard fd 0-2 */
+
+ (void)dup2(fd, 0);
+ (void)dup2(fd, 1);
+ (void)dup2(fd, 2);
+
+ /* fdopen to get the stdin, stdout and stderr streams. The following logic depends
+ * on the fact that the library layer will allocate FILEs in order. And since
+ * we closed stdin, stdout, and stderr above, that is what we should get.
+ *
+ * fd = 0 is stdin (read-only)
+ * fd = 1 is stdout (write-only, append)
+ * fd = 2 is stderr (write-only, append)
+ */
+
+ (void)fdopen(0, "r");
+ (void)fdopen(1, "a");
+ (void)fdopen(2, "a");
+}
+#endif
+
/****************************************************************************
- * Name: nsh_usbconsole
+ * Name: nsh_nullstdio
+ *
+ * Description:
+ * Use /dev/null for standard I/O
+ *
****************************************************************************/
#ifdef HAVE_USB_CONSOLE
-int nsh_usbconsole(void)
+static int nsh_nullstdio(void)
{
- char inch;
- ssize_t nbytes;
- int nlc;
int fd;
- int ret;
- /* Initialize any USB tracing options that were requested */
+ /* Open /dev/null for read/write access */
-#ifdef CONFIG_USBDEV_TRACE
- usbtrace_enable(TRACE_BITSET);
+ fd = open("/dev/null", O_RDWR);
+ if (fd >= 0)
+ {
+ /* Configure standard I/O to use /dev/null */
+
+ nsh_configstdio(fd);
+
+ /* We can close the original file descriptor now (unless it was one of
+ * 0-2)
+ */
+
+ if (fd > 2)
+ {
+ close(fd);
+ }
+
+ return OK;
+ }
+
+ return fd;
+}
#endif
+/****************************************************************************
+ * Name: nsh_waitusbready
+ *
+ * Description:
+ * Wait for the USB console device to be ready
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_USB_CONSOLE
+static int nsh_waitusbready(void)
+{
+ char inch;
+ ssize_t nbytes;
+ int nlc;
+ int fd;
+
/* Don't start the NSH console until the console device is ready. Chances
* are, we get here with no functional console. The USB console will not
* be available until the device is connected to the host and until the
* host-side application opens the connection.
*/
- /* Initialize the USB serial driver */
-
-#if defined(CONFIG_PL2303) || defined(CONFIG_CDCACM)
-#ifdef CONFIG_CDCACM
- ret = cdcacm_initialize(CONFIG_NSH_UBSDEV_MINOR, NULL);
-#else
- ret = usbdev_serialinitialize(CONFIG_NSH_UBSDEV_MINOR);
-#endif
- DEBUGASSERT(ret == OK);
-#endif
-
/* Open the USB serial device for read/write access */
do
@@ -193,17 +264,9 @@ int nsh_usbconsole(void)
}
while (nlc < 3);
- /* Make sure the stdin, stdout, and stderr are closed */
-
- (void)fclose(stdin);
- (void)fclose(stdout);
- (void)fclose(stderr);
+ /* Configure standard I/O */
- /* Dup the fd to create standard fd 0-2 */
-
- (void)dup2(fd, 0);
- (void)dup2(fd, 1);
- (void)dup2(fd, 2);
+ nsh_configstdio(fd);
/* We can close the original file descriptor now (unless it was one of 0-2) */
@@ -212,32 +275,117 @@ int nsh_usbconsole(void)
close(fd);
}
- /* fdopen to get the stdin, stdout and stderr streams. The following logic depends
- * on the fact that the library layer will allocate FILEs in order. And since
- * we closed stdin, stdout, and stderr above, that is what we should get.
- *
- * fd = 0 is stdin (read-only)
- * fd = 1 is stdout (write-only, append)
- * fd = 2 is stderr (write-only, append)
- */
-
- (void)fdopen(0, "r");
- (void)fdopen(1, "a");
- (void)fdopen(2, "a");
return OK;
}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_consolemain (USB console version)
+ *
+ * Description:
+ * This interfaces maybe to called or started with task_start to start a
+ * single an NSH instance that operates on stdin and stdout. This
+ * function does not return.
+ *
+ * This function handles generic /dev/console character devices, or
+ * special USB console devices. The USB console requires some special
+ * operations to handle the cases where the session is lost when the
+ * USB device is unplugged and restarted when the USB device is plugged
+ * in again.
+ *
+ * Input Parameters:
+ * Standard task start-up arguments. These are not used. argc may be
+ * zero and argv may be NULL.
+ *
+ * Returned Values:
+ * This function does not return nor does it ever exit (unless the user
+ * executes the NSH exit command).
+ *
+ ****************************************************************************/
+
+#ifdef HAVE_USB_CONSOLE
+int nsh_consolemain(int argc, char *argv[])
+{
+ FAR struct console_stdio_s *pstate = nsh_newconsole();
+ int ret;
+
+ DEBUGASSERT(pstate);
+
+ /* Initialize any USB tracing options that were requested */
+
+#ifdef CONFIG_NSH_USBDEV_TRACE
+ usbtrace_enable(TRACE_BITSET);
+#endif
+
+ /* Initialize the USB serial driver */
-#endif /* HAVE_USB_CONSOLE */
+#if defined(CONFIG_PL2303) || defined(CONFIG_CDCACM)
+#ifdef CONFIG_CDCACM
+ ret = cdcacm_initialize(CONFIG_NSH_USBDEV_MINOR, NULL);
+#else
+ ret = usbdev_serialinitialize(CONFIG_NSH_USBDEV_MINOR);
+#endif
+ DEBUGASSERT(ret == OK);
+#endif
+
+ /* Configure to use /dev/null if we do not have a valid console. */
+
+#ifndef CONFIG_DEV_CONSOLE
+ (void)nsh_nullstdio();
+#endif
+
+ /* Execute the one-time start-up script (output may go to /dev/null) */
+
+#ifdef CONFIG_NSH_ROMFSETC
+ (void)nsh_initscript(&pstate->cn_vtbl);
+#endif
+
+ /* Now loop, executing creating a session for each USB connection */
+
+ for (;;)
+ {
+ /* Wait for the USB to be connected to the host and switch
+ * standard I/O to the USB serial device.
+ */
+
+ ret = nsh_waitusbready();
+ DEBUGASSERT(ret == OK);
+
+ /* Execute the session */
+
+ (void)nsh_session(pstate);
+
+ /* Switch to /dev/null because we probably no longer have a
+ * valid console device.
+ */
+
+ (void)nsh_nullstdio();
+ }
+}
+#endif
/****************************************************************************
* Name: nsh_usbtrace
+ *
+ * Description:
+ * The function is called from the nsh_session() to dump USB data to the
+ * SYSLOG device.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Values:
+ * None
+ *
****************************************************************************/
-#if defined(CONFIG_USBDEV_TRACE) && defined(HAVE_USB_CONSOLE)
+#ifdef CONFIG_NSH_USBDEV_TRACE
void nsh_usbtrace(void)
{
(void)usbtrace_enumerate(nsh_tracecallback, NULL);
}
#endif
-
-#endif /* CONFIG_USBDEV */
diff --git a/apps/px4/tests/test_adc.c b/apps/px4/tests/test_adc.c
index 4c021303f..030ac6e23 100644
--- a/apps/px4/tests/test_adc.c
+++ b/apps/px4/tests/test_adc.c
@@ -60,8 +60,10 @@ int test_adc(int argc, char *argv[])
{
int fd = open(ADC_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
- err(1, "can't open ADC device");
+ if (fd < 0) {
+ warnx("ERROR: can't open ADC device");
+ return 1;
+ }
for (unsigned i = 0; i < 5; i++) {
/* make space for a maximum of eight channels */
@@ -82,7 +84,7 @@ int test_adc(int argc, char *argv[])
usleep(150000);
}
- message("\t ADC test successful.\n");
+ warnx("\t ADC test successful.\n");
errout_with_dev:
diff --git a/apps/px4/tests/tests.h b/apps/px4/tests/tests.h
index cc3f5493a..c02ea6808 100644
--- a/apps/px4/tests/tests.h
+++ b/apps/px4/tests/tests.h
@@ -48,7 +48,7 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
-# define message(...) lib_rawprintf(__VA_ARGS__)
+# define message(...) lowsyslog(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
@@ -56,7 +56,7 @@
# endif
#else
# ifdef CONFIG_DEBUG
-# define message lib_rawprintf
+# define message lowsyslog
# define msgflush()
# else
# define message printf
diff --git a/apps/px4/tests/tests_main.c b/apps/px4/tests/tests_main.c
index ad6828f20..9f8c5c9ea 100644
--- a/apps/px4/tests/tests_main.c
+++ b/apps/px4/tests/tests_main.c
@@ -135,6 +135,7 @@ test_all(int argc, char *argv[])
unsigned i;
char *args[2] = {"all", NULL};
unsigned int failcount = 0;
+ unsigned int testcount = 0;
bool passed[NTESTS];
printf("\nRunning all tests...\n\n");
@@ -156,6 +157,7 @@ test_all(int argc, char *argv[])
fflush(stdout);
passed[i] = true;
}
+ testcount++;
}
}
@@ -178,7 +180,7 @@ test_all(int argc, char *argv[])
printf(" \\ \\_\\ \\_\\ \\ \\_____\\ \\ \\_____\\ \\ \\_____\\ \\ \\_\\ \\_\\ \n");
printf(" \\/_/\\/_/ \\/_____/ \\/_____/ \\/_____/ \\/_/\\/_/ \n");
printf("\n");
- printf(" All tests passed (%d of %d)\n", i, i);
+ printf(" All tests passed (%d of %d)\n", testcount, testcount);
} else {
printf(" ______ ______ __ __ \n");
@@ -187,7 +189,7 @@ test_all(int argc, char *argv[])
printf(" \\ \\_\\ \\ \\_\\ \\_\\ \\ \\_\\ \\ \\_____\\ \n");
printf(" \\/_/ \\/_/\\/_/ \\/_/ \\/_____/ \n");
printf("\n");
- printf(" Some tests failed (%d of %d)\n", failcount, i);
+ printf(" Some tests failed (%d of %d)\n", failcount, testcount);
}
printf("\n");
@@ -245,6 +247,7 @@ int test_jig(int argc, char *argv[])
unsigned i;
char *args[2] = {"jig", NULL};
unsigned int failcount = 0;
+ unsigned int testcount = 0;
bool passed[NTESTS];
printf("\nRunning all tests...\n\n");
@@ -264,6 +267,7 @@ int test_jig(int argc, char *argv[])
fflush(stdout);
passed[i] = true;
}
+ testcount++;
}
}
@@ -284,7 +288,7 @@ int test_jig(int argc, char *argv[])
printf(" \\ \\_\\ \\_\\ \\ \\_____\\ \\ \\_____\\ \\ \\_____\\ \\ \\_\\ \\_\\ \n");
printf(" \\/_/\\/_/ \\/_____/ \\/_____/ \\/_____/ \\/_/\\/_/ \n");
printf("\n");
- printf(" All tests passed (%d of %d)\n", i, i);
+ printf(" All tests passed (%d of %d)\n", testcount, testcount);
} else {
printf(" ______ ______ __ __ \n");
printf(" /\\ ___\\ /\\ __ \\ /\\ \\ /\\ \\ \n");
@@ -292,7 +296,7 @@ int test_jig(int argc, char *argv[])
printf(" \\ \\_\\ \\ \\_\\ \\_\\ \\ \\_\\ \\ \\_____\\ \n");
printf(" \\/_/ \\/_/\\/_/ \\/_/ \\/_____/ \n");
printf("\n");
- printf(" Some tests failed (%d of %d)\n", failcount, i);
+ printf(" Some tests failed (%d of %d)\n", failcount, testcount);
}
printf("\n");
diff --git a/apps/px4io/mixer.cpp b/apps/px4io/mixer.cpp
index c24cb8e52..8e00781a0 100644
--- a/apps/px4io/mixer.cpp
+++ b/apps/px4io/mixer.cpp
@@ -144,7 +144,7 @@ mixer_tick(void)
rc_channel_data[THROTTLE] = 1000;
}
- // lib_lowprintf("Tmin: %d Ttrim: %d Tmax: %d T: %d \n",
+ // lowsyslog("Tmin: %d Ttrim: %d Tmax: %d T: %d \n",
// (int)(system_state.rc_min[THROTTLE]), (int)(system_state.rc_trim[THROTTLE]),
// (int)(system_state.rc_max[THROTTLE]), (int)(rc_channel_data[THROTTLE]));
@@ -156,7 +156,7 @@ mixer_tick(void)
// XXX builtin failsafe would activate here
control_count = 0;
}
- //lib_lowprintf("R: %d P: %d Y: %d T: %d \n", control_values[0], control_values[1], control_values[2], control_values[3]);
+ //lowsyslog("R: %d P: %d Y: %d T: %d \n", control_values[0], control_values[1], control_values[2], control_values[3]);
/* this is for multicopters, etc. where manual override does not make sense */
} else {
diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c
index bea9d59bc..88342816e 100644
--- a/apps/px4io/px4io.c
+++ b/apps/px4io/px4io.c
@@ -73,7 +73,7 @@ int user_start(int argc, char *argv[])
hrt_init();
/* print some startup info */
- lib_lowprintf("\nPX4IO: starting\n");
+ lowsyslog("\nPX4IO: starting\n");
/* default all the LEDs to off while we start */
LED_AMBER(false);
@@ -98,7 +98,7 @@ int user_start(int argc, char *argv[])
struct mallinfo minfo = mallinfo();
- lib_lowprintf("free %u largest %u\n", minfo.mxordblk, minfo.fordblks);
+ lowsyslog("free %u largest %u\n", minfo.mxordblk, minfo.fordblks);
/* we're done here, go run the communications loop */
comms_main();
diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h
index e388f65e3..3ce6afc31 100644
--- a/apps/px4io/px4io.h
+++ b/apps/px4io/px4io.h
@@ -58,7 +58,7 @@
#ifdef DEBUG
# include <debug.h>
-# define debug(fmt, args...) lib_lowprintf(fmt "\n", ##args)
+# define debug(fmt, args...) lowsyslog(fmt "\n", ##args)
#else
# define debug(fmt, args...) do {} while(0)
#endif
diff --git a/apps/system/Kconfig b/apps/system/Kconfig
index d4d434665..6c8651088 100644
--- a/apps/system/Kconfig
+++ b/apps/system/Kconfig
@@ -34,3 +34,7 @@ endmenu
menu "Sysinfo"
source "$APPSDIR/system/sysinfo/Kconfig"
endmenu
+
+menu "USB Monitor"
+source "$APPSDIR/system/usbmonitor/Kconfig"
+endmenu
diff --git a/apps/system/Make.defs b/apps/system/Make.defs
index 3d10f84e5..3c679f112 100644
--- a/apps/system/Make.defs
+++ b/apps/system/Make.defs
@@ -66,3 +66,6 @@ ifeq ($(CONFIG_SYSTEM_SYSINFO),y)
CONFIGURED_APPS += system/sysinfo
endif
+ifeq ($(CONFIG_SYSTEM_USBMONITOR),y)
+CONFIGURED_APPS += system/usbmonitor
+endif
diff --git a/apps/system/Makefile b/apps/system/Makefile
index 057fbcf77..f39eedec4 100644
--- a/apps/system/Makefile
+++ b/apps/system/Makefile
@@ -37,7 +37,7 @@
# Sub-directories containing system task
-SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo
+SUBDIRS = free i2c install readline poweroff ramtron sdcard sysinfo usbmonitor
# Create the list of installed runtime modules (INSTALLED_DIRS)
diff --git a/apps/system/free/README.txt b/apps/system/free/README.txt
deleted file mode 100644
index 1c2d380d4..000000000
--- a/apps/system/free/README.txt
+++ /dev/null
@@ -1,6 +0,0 @@
-
-This application provides UNIX style memory free information.
-
- Source: NuttX
- Author: Gregory Nutt <gnutt@nuttx.org>
- Date: 17. March 2011
diff --git a/apps/system/readline/readline.c b/apps/system/readline/readline.c
index f64049ed7..bac7eee8c 100644
--- a/apps/system/readline/readline.c
+++ b/apps/system/readline/readline.c
@@ -132,23 +132,33 @@ static inline int readline_rawgetc(int infd)
nread = read(infd, &buffer, 1);
- /* Return EOF if the end of file (0) or error (-1) occurs. */
+ /* Check for end-of-file. */
- if (nread < 1)
+ if (nread == 0)
+ {
+ /* Return zero on end-of-file */
+
+ return 0;
+ }
+
+ /* Check if an error occurred */
+
+ else if (nread < 0)
{
/* EINTR is not really an error; it simply means that a signal we
* received while watiing for intput.
*/
- if (nread == 0 || errno != EINTR)
+ int errcode = errno;
+ if (errcode != EINTR)
{
- return EOF;
+ return -errcode;
}
}
}
while (nread < 1);
- /* On success, returnt he character that was read */
+ /* On success, return the character that was read */
return (int)buffer;
}
@@ -275,9 +285,29 @@ ssize_t readline(FAR char *buf, int buflen, FILE *instream, FILE *outstream)
int ch = readline_rawgetc(infd);
+ /* Check for end-of-file or read error */
+
+ if (ch <= 0)
+ {
+ /* Did we already received some data? */
+
+ if (nch > 0)
+ {
+ /* Yes.. Terminate the line (which might be zero length)
+ * and return the data that was received. The end-of-file
+ * or error condition will be reported next time.
+ */
+
+ buf[nch] = '\0';
+ return nch;
+ }
+
+ return ch;
+ }
+
/* Are we processing a VT100 escape sequence */
- if (escape)
+ else if (escape)
{
/* Yes, is it an <esc>[, 3 byte sequence */
@@ -366,16 +396,6 @@ ssize_t readline(FAR char *buf, int buflen, FILE *instream, FILE *outstream)
return nch;
}
- /* Check for end-of-file */
-
- else if (ch == EOF)
- {
- /* Terminate the line (which might be zero length) */
-
- buf[nch] = '\0';
- return nch;
- }
-
/* Otherwise, check if the character is printable and, if so, put the
* character in the line buffer
*/
diff --git a/apps/system/usbmonitor/Kconfig b/apps/system/usbmonitor/Kconfig
new file mode 100644
index 000000000..bde97de15
--- /dev/null
+++ b/apps/system/usbmonitor/Kconfig
@@ -0,0 +1,67 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config SYSTEM_USBMONITOR
+ bool "USB Monitor"
+ default n
+ depends on USBDEV && USBDEV_TRACE && SYSLOG
+ ---help---
+ If USB device tracing is enabled (USBDEV_TRACE), then this option
+ will select the USB monitor. The USB monitor is a daemon that will
+ periodically collect the buffered USB trace data and dump it to the
+ SYSLOG device.
+
+if SYSTEM_USBMONITOR
+
+config SYSTEM_USBMONITOR_STACKSIZE
+ int "USB Monitor daemon stack size"
+ default 2048
+ ---help---
+ The stack size to use the the USB monitor daemon. Default: 2048
+
+config SYSTEM_USBMONITOR_PRIORITY
+ int "USB Monitor daemon priority"
+ default 50
+ ---help---
+ The priority to use the the USB monitor daemon. Default: 50
+
+config SYSTEM_USBMONITOR_INTERVAL
+ int "USB Monitor dump frequency"
+ default 2
+ ---help---
+ The rate in seconds that the USB monitor will wait before dumping
+ the next set of buffered USB trace data. Default: 2 seconds.
+
+config SYSTEM_USBMONITOR_TRACEINIT
+ bool "Show initialization events"
+ default n
+ ---help---
+ Show initialization events
+
+config SYSTEM_USBMONITOR_TRACECLASS
+ bool "Show class driver events"
+ default n
+ ---help---
+ Show class driver events
+
+config SYSTEM_USBMONITOR_TRACETRANSFERS
+ bool "Show data transfer events"
+ default n
+ ---help---
+ Show data transfer events
+
+config SYSTEM_USBMONITOR_TRACECONTROLLER
+ bool "Show controller events"
+ default n
+ ---help---
+ Show controller events
+
+config SYSTEM_USBMONITOR_TRACEINTERRUPTS
+ bool "Show interrupt-related events"
+ default n
+ ---help---
+ Show interrupt-related events
+endif
+
diff --git a/apps/system/usbmonitor/Makefile b/apps/system/usbmonitor/Makefile
new file mode 100644
index 000000000..56b6ccee1
--- /dev/null
+++ b/apps/system/usbmonitor/Makefile
@@ -0,0 +1,117 @@
+############################################################################
+# apps/system/usbmonitor/Makefile
+#
+# Copyright (C) 2013 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.
+#
+############################################################################
+
+-include $(TOPDIR)/.config
+-include $(TOPDIR)/Make.defs
+include $(APPDIR)/Make.defs
+
+ifeq ($(WINTOOL),y)
+INCDIROPT = -w
+endif
+
+# USB Monitor Application
+
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 768
+
+ASRCS =
+CSRCS = usbmonitor.c
+
+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
+
+# Register application
+
+ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
+$(BUILTIN_REGISTRY)$(DELIM)usbmonitor_start.bdat: $(DEPCONFIG) Makefile
+ $(call REGISTER,"usbmon_start",$(PRIORITY),$(STACKSIZE),usbmonitor_start)
+
+$(BUILTIN_REGISTRY)$(DELIM)usbmonitor_stop.bdat: $(DEPCONFIG) Makefile
+ $(call REGISTER,"usbmon_stop",$(PRIORITY),$(STACKSIZE),usbmonitor_stop)
+
+context: $(BUILTIN_REGISTRY)$(DELIM)usbmonitor_start.bdat $(BUILTIN_REGISTRY)$(DELIM)usbmonitor_stop.bdat
+else
+context:
+endif
+
+# Create dependencies
+
+.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/system/usbmonitor/usbmonitor.c b/apps/system/usbmonitor/usbmonitor.c
new file mode 100644
index 000000000..cde945b43
--- /dev/null
+++ b/apps/system/usbmonitor/usbmonitor.c
@@ -0,0 +1,234 @@
+/****************************************************************************
+ * apps/system/usbmonitor/usbmonitor.c
+ *
+ * Copyright (C) 2013 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 <nuttx/progmem.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <sched.h>
+#include <syslog.h>
+#include <errno.h>
+
+#include <nuttx/usb/usbdev_trace.h>
+
+#ifdef CONFIG_SYSTEM_USBMONITOR
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define USBMON_PREFIX "USB Monitor: "
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_SYSTEM_USBMONITOR_STACKSIZE
+# define CONFIG_SYSTEM_USBMONITOR_STACKSIZE 2048
+#endif
+
+#ifndef CONFIG_SYSTEM_USBMONITOR_PRIORITY
+# define CONFIG_SYSTEM_USBMONITOR_PRIORITY 50
+#endif
+
+#ifndef CONFIG_SYSTEM_USBMONITOR_INTERVAL
+# define CONFIG_SYSTEM_USBMONITOR_INTERVAL 2
+#endif
+
+#ifdef CONFIG_SYSTEM_USBMONITOR_TRACEINIT
+# define TRACE_INIT_BITS (TRACE_INIT_BIT)
+#else
+# define TRACE_INIT_BITS (0)
+#endif
+
+#define TRACE_ERROR_BITS (TRACE_DEVERROR_BIT|TRACE_CLSERROR_BIT)
+
+#ifdef CONFIG_SYSTEM_USBMONITOR_TRACECLASS
+# define TRACE_CLASS_BITS (TRACE_CLASS_BIT|TRACE_CLASSAPI_BIT|\
+ TRACE_CLASSSTATE_BIT)
+#else
+# define TRACE_CLASS_BITS (0)
+#endif
+
+#ifdef CONFIG_SYSTEM_USBMONITOR_TRACETRANSFERS
+# define TRACE_TRANSFER_BITS (TRACE_OUTREQQUEUED_BIT|TRACE_INREQQUEUED_BIT|\
+ TRACE_READ_BIT|TRACE_WRITE_BIT|\
+ TRACE_COMPLETE_BIT)
+#else
+# define TRACE_TRANSFER_BITS (0)
+#endif
+
+#ifdef CONFIG_SYSTEM_USBMONITOR_TRACECONTROLLER
+# define TRACE_CONTROLLER_BITS (TRACE_EP_BIT|TRACE_DEV_BIT)
+#else
+# define TRACE_CONTROLLER_BITS (0)
+#endif
+
+#ifdef CONFIG_SYSTEM_USBMONITOR_TRACEINTERRUPTS
+# define TRACE_INTERRUPT_BITS (TRACE_INTENTRY_BIT|TRACE_INTDECODE_BIT|\
+ TRACE_INTEXIT_BIT)
+#else
+# define TRACE_INTERRUPT_BITS (0)
+#endif
+
+#define TRACE_BITSET (TRACE_INIT_BITS|TRACE_ERROR_BITS|\
+ TRACE_CLASS_BITS|TRACE_TRANSFER_BITS|\
+ TRACE_CONTROLLER_BITS|TRACE_INTERRUPT_BITS)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct usbmon_state_s
+{
+ volatile bool started;
+ volatile bool stop;
+ pid_t pid;
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct usbmon_state_s g_usbmonitor;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static int usbmonitor_tracecallback(struct usbtrace_s *trace, void *arg)
+{
+ usbtrace_trprintf((trprintf_t)syslog, trace->event, trace->value);
+ return 0;
+}
+
+static int usbmonitor_daemon(int argc, char **argv)
+{
+ syslog(USBMON_PREFIX "Running: %d\n", g_usbmonitor.pid);
+
+ /* Loop until we detect that there is a request to stop. */
+
+ while (!g_usbmonitor.stop)
+ {
+ sleep(CONFIG_SYSTEM_USBMONITOR_INTERVAL);
+ (void)usbtrace_enumerate(usbmonitor_tracecallback, NULL);
+ }
+
+ /* Stopped */
+
+ g_usbmonitor.stop = false;
+ g_usbmonitor.started = false;
+ syslog(USBMON_PREFIX "Stopped: %d\n", g_usbmonitor.pid);
+
+ return 0;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int usbmonitor_start(int argc, char **argv)
+{
+ /* Has the monitor already started? */
+
+ sched_lock();
+ if (!g_usbmonitor.started)
+ {
+ int ret;
+
+ /* No.. start it now */
+
+ /* First, initialize any USB tracing options that were requested */
+
+ usbtrace_enable(TRACE_BITSET);
+
+ /* Then start the USB monitoring daemon */
+
+ g_usbmonitor.started = true;
+ g_usbmonitor.stop = false;
+
+ ret = TASK_CREATE("USB Monitor", CONFIG_SYSTEM_USBMONITOR_PRIORITY,
+ CONFIG_SYSTEM_USBMONITOR_STACKSIZE,
+ (main_t)usbmonitor_daemon, (const char **)NULL);
+ if (ret < 0)
+ {
+ int errcode = errno;
+ syslog(USBMON_PREFIX
+ "ERROR: Failed to start the USB monitor: %d\n",
+ errcode);
+ }
+ else
+ {
+ g_usbmonitor.pid = ret;
+ syslog(USBMON_PREFIX "Started: %d\n", g_usbmonitor.pid);
+ }
+
+ sched_unlock();
+ return 0;
+ }
+
+ sched_unlock();
+ syslog(USBMON_PREFIX "%s: %d\n",
+ g_usbmonitor.stop ? "Stopping" : "Running", g_usbmonitor.pid);
+ return 0;
+}
+
+int usbmonitor_stop(int argc, char **argv)
+{
+ /* Has the monitor already started? */
+
+ if (g_usbmonitor.started)
+ {
+ /* Stop the USB monitor. The next time the monitor wakes up,
+ * it will see the the stop indication and will exist.
+ */
+
+ syslog(USBMON_PREFIX "Stopping: %d\n", g_usbmonitor.pid);
+ g_usbmonitor.stop = true;
+
+ /* We may as well disable tracing since there is no listener */
+
+ usbtrace_enable(0);
+ }
+
+ syslog(USBMON_PREFIX "Stopped: %d\n", g_usbmonitor.pid);
+ return 0;
+}
+
+#endif /* CONFIG_SYSTEM_USBMONITOR */
diff --git a/apps/systemlib/err.c b/apps/systemlib/err.c
index 3011743a1..daf17ef8b 100644
--- a/apps/systemlib/err.c
+++ b/apps/systemlib/err.c
@@ -85,17 +85,17 @@ warnerr_core(int errcode, const char *fmt, va_list args)
fprintf(stderr, "\n");
#elif CONFIG_ARCH_LOWPUTC
- lib_lowprintf("%s: ", getprogname());
- lib_lowvprintf(fmt, args);
+ lowsyslog("%s: ", getprogname());
+ lowvyslog(fmt, args);
/* convenience as many parts of NuttX use negative errno */
if (errcode < 0)
errcode = -errcode;
if (errcode < NOCODE)
- lib_lowprintf(": %s", strerror(errcode));
+ lowsyslog(": %s", strerror(errcode));
- lib_lowprintf("\n");
+ lowsyslog("\n");
#endif
}
diff --git a/apps/systemlib/mixer/mixer_group.cpp b/apps/systemlib/mixer/mixer_group.cpp
index 25d19f9ad..60eeff225 100644
--- a/apps/systemlib/mixer/mixer_group.cpp
+++ b/apps/systemlib/mixer/mixer_group.cpp
@@ -56,7 +56,7 @@
#define debug(fmt, args...) do { } while(0)
//#define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
//#include <debug.h>
-//#define debug(fmt, args...) lib_lowprintf(fmt "\n", ##args)
+//#define debug(fmt, args...) lowsyslog(fmt "\n", ##args)
MixerGroup::MixerGroup(ControlCallback control_cb, uintptr_t cb_handle) :
Mixer(control_cb, cb_handle),
diff --git a/apps/systemlib/mixer/mixer_multirotor.cpp b/apps/systemlib/mixer/mixer_multirotor.cpp
index f6e91b1bf..4b9cfc023 100644
--- a/apps/systemlib/mixer/mixer_multirotor.cpp
+++ b/apps/systemlib/mixer/mixer_multirotor.cpp
@@ -57,7 +57,7 @@
#define debug(fmt, args...) do { } while(0)
//#define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
//#include <debug.h>
-//#define debug(fmt, args...) lib_lowprintf(fmt "\n", ##args)
+//#define debug(fmt, args...) lowsyslog(fmt "\n", ##args)
/*
* Clockwise: 1
@@ -217,11 +217,11 @@ unsigned
MultirotorMixer::mix(float *outputs, unsigned space)
{
float roll = get_control(0, 0) * _roll_scale;
- //lib_lowprintf("roll: %d, get_control0: %d, %d\n", (int)(roll), (int)(get_control(0, 0)), (int)(_roll_scale));
+ //lowsyslog("roll: %d, get_control0: %d, %d\n", (int)(roll), (int)(get_control(0, 0)), (int)(_roll_scale));
float pitch = get_control(0, 1) * _pitch_scale;
float yaw = get_control(0, 2) * _yaw_scale;
float thrust = get_control(0, 3);
- //lib_lowprintf("thrust: %d, get_control3: %d\n", (int)(thrust), (int)(get_control(0, 3)));
+ //lowsyslog("thrust: %d, get_control3: %d\n", (int)(thrust), (int)(get_control(0, 3)));
float max = 0.0f;
float fixup_scale;
diff --git a/apps/uORB/topics/home_position.h b/apps/uORB/topics/home_position.h
index dec34b6ab..7e1b82a0f 100644
--- a/apps/uORB/topics/home_position.h
+++ b/apps/uORB/topics/home_position.h
@@ -61,10 +61,10 @@ struct home_position_s
int32_t lat; /**< Latitude in 1E7 degrees */
int32_t lon; /**< Longitude in 1E7 degrees */
int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
- uint16_t eph; /**< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */
- uint16_t epv; /**< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */
- float s_variance; /**< speed accuracy estimate cm/s */
- float p_variance; /**< position accuracy estimate cm */
+ float eph_m; /**< GPS HDOP horizontal dilution of position in m */
+ float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+ float s_variance_m_s; /**< speed accuracy estimate m/s */
+ float p_variance_m; /**< position accuracy estimate m */
};
/**
diff --git a/apps/uORB/topics/vehicle_gps_position.h b/apps/uORB/topics/vehicle_gps_position.h
index db529da06..5463a460d 100644
--- a/apps/uORB/topics/vehicle_gps_position.h
+++ b/apps/uORB/topics/vehicle_gps_position.h
@@ -55,35 +55,38 @@
*/
struct vehicle_gps_position_s
{
- uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
- uint32_t counter; /**< Count of GPS messages */
- uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
+ uint64_t timestamp_position; /**< Timestamp for position information */
+ int32_t lat; /**< Latitude in 1E7 degrees */
+ int32_t lon; /**< Longitude in 1E7 degrees */
+ int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
- int32_t lat; /**< Latitude in 1E7 degrees //LOGME */
- int32_t lon; /**< Longitude in 1E7 degrees //LOGME */
- int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL //LOGME */
- uint16_t counter_pos_valid; /**< is only increased when new lat/lon/alt information was added */
- uint16_t eph; /**< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 //LOGME */
- uint16_t epv; /**< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */
- float s_variance; /**< speed accuracy estimate cm/s */
- float p_variance; /**< position accuracy estimate cm */
- uint16_t vel; /**< GPS ground speed (m/s * 100). If unknown, set to: 65535 */
- float vel_n; /**< GPS ground speed in m/s */
- float vel_e; /**< GPS ground speed in m/s */
- float vel_d; /**< GPS ground speed in m/s */
- uint16_t cog; /**< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 */
- uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
- uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */
+ uint64_t timestamp_variance;
+ float s_variance_m_s; /**< speed accuracy estimate m/s */
+ float p_variance_m; /**< position accuracy estimate m */
+ uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
- uint8_t satellite_prn[20]; /**< Global satellite ID */
- uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
- uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
- uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
- uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
- uint8_t satellite_info_available; /**< 0 for no info, 1 for info available */
+ float eph_m; /**< GPS HDOP horizontal dilution of position in m */
+ float epv_m; /**< GPS VDOP horizontal dilution of position in m */
- /* flags */
- float vel_ned_valid; /**< Flag to indicate if NED speed is valid */
+ uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
+ float vel_m_s; /**< GPS ground speed (m/s) */
+ float vel_n_m_s; /**< GPS ground speed in m/s */
+ float vel_e_m_s; /**< GPS ground speed in m/s */
+ float vel_d_m_s; /**< GPS ground speed in m/s */
+ float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad */
+ bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */
+
+ uint64_t timestamp_time; /**< Timestamp for time information */
+ uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
+
+ uint64_t timestamp_satellites; /**< Timestamp for sattelite information */
+ uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */
+ uint8_t satellite_prn[20]; /**< Global satellite ID */
+ uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
+ uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
+ uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
+ uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
+ bool satellite_info_available; /**< 0 for no info, 1 for info available */
};
/**
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 99f6d4a52..5bdd1aad8 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3800,7 +3800,7 @@
* configs/stm32f4discovery/elf: Enable support/test of the PATH
to find executables using a relative path.
-6.25 2013-xx-xx Gregory Nutt <gnutt@nuttx.org>
+6.25 2013-02-01 Gregory Nutt <gnutt@nuttx.org>
* graphics/: Adds 5x8 monospace font. This tiny font is useful for graph
labels and for small bitmapped display. Contributed by Petteri
@@ -3833,7 +3833,7 @@
* drivers/usbhost/usbhost_hidkbd.c: Correct a logic error in how
tasks waiting for read data are awakened.
* libc/misc/lib_kbdencode.c and lib_kbddecode.c: Now handles keypress
- events too. However, the USB HID keyboard drier has not yet been
+ events too. However, the USB HID keyboard driver has not yet been
updated to detect key release events. That is kind of tricky in
the USB HID keyboard report data.
* configs/mcu123-214x/nsh: Converted to use the kconfig-frontends
@@ -3857,7 +3857,7 @@
buildroot toolchains: They may be EABI or OABI.
* include/nuttx/progmem and arch/arm/src/stm32/stm32_flash.c:
Fix a counting bug plus change interface to use either relative
- or absolut FLASH addressing (from Freddie Chopin).
+ or absolute FLASH addressing (from Freddie Chopin).
* libc/misc/Make.defs: Fix error in conditional for KBD CODEC.
* libc/Kconfig and configs/*/defconfig (several): The default
setting should be CONFIG_LIB_KBDCODEC=n
@@ -3868,7 +3868,7 @@
* tools/configure.bat: configure.bat is a small Windows batch
file that can be used as a replacement for configure.sh in a
Windows native environment. configure.bat is actually just a
- thin layer that execuates configure.exe if it is available. If
+ thin layer that executes configure.exe if it is available. If
configure.exe is not available, then configure.bat will attempt
to build it first.
* arch/arm/src/lpc17xx/lpc17_syscon.h: Correct some typos in bit
@@ -3918,12 +3918,12 @@
the scenario: (1) sched_lock() is called increments the lockcount
on the current TCB (i.e., the one at the head of the ready to run
list), (2) sched_mergepending is called which may change the task
- at the head of the readytorun list, then (2) sched_unlock() is called
+ at the head of the ready-to-run list, then (3) sched_unlock() is called
which decrements the lockcount on the wrong TCB. The failure case
that I saw was that pre-emption got disabled in the IDLE thread,
locking up the whole system.
* sched/sched_waitpid.c: Use SIGCHLD instead of a semaphore. This
- is a much more spec-compliant implemenation. However, there are
+ is a much more spec-compliant implementation. However, there are
some issues with overruning signals because NuttX does not support
queueing of signals (POSIX does not require it). I think it may
need to.
@@ -3959,7 +3959,7 @@
CONFIG_APPS_BINDIR rename CONFIG_FS_BINFS
* include/nuttx/binfmt/builtin.h: Some of the content of
apps/include/apps.h moved to include/nuttx/binfmt/builtin.h
- * binfmt/libbuiltin/libbuiltin_utils.c: Move utility builtin
+ * binfmt/libbuiltin/libbuiltin_utils.c: Move builtin
utility functions from apps/builtin/exec_builtins.c to
binfmt/libbuiltin/libbuiltin_utils.c
* binfmt/builtin.c and binfmt/libbuiltin: Add a binary "loader"
@@ -3985,7 +3985,7 @@
* arch/arm/src/[many]: More LPC1788 definitions from Rommel
Marcelo incorporated.
* configs/open1788: Board configuration for the Wave Share
- Open1788 board. Still fragmentary (contribnuted by Rommel
+ Open1788 board. Still fragmentary (contributed by Rommel
Marcelo, adapted to use kconfig-frontends.
* net/send(): Add logic to work around delayed ACKs by splitting
packets (contributed by Yan T.).
@@ -4011,11 +4011,92 @@
* arch/armv7-m/up_hardfault.c: Fail if a hardfault occurs
while CONFIG_ARM7VM_USEBASEPRI=y.
* arch/arm/src/stm32/stm32_serial.c: Add support for USART
- single wire more (Contributed by the PX4 team).
+ single wire mode (Contributed by the PX4 team).
* sched/: Implement support for retaining child task status after
the child task exists. This is behavior required by POSIX.
But in NuttX is only enabled with CONFIG_SCHED_HAVE_PARENT and
CONFIG_SCHED_CHILD_STATUS
* Add support for keyboard encode to the keypad test (from
Denis Carikli).
-
+ * configs/olimex-lpc1766stk/nettest: Configuration converted to
+ use the kconfig-frontends tools.
+ * net/net_poll.c: Split net_poll() to create psock_poll() too.
+ * net/net_poll.c: Fix poll/select issure reported by Qiang:
+ poll_interrupt() must call net_lostconnection() when a
+ loss of connection is reported. Otherwise, the system will
+ not know that the connection has been lost.
+ * sched/group_create.c, group_join.c, and group_leave.c: Add
+ support for task groups.
+ * sched/group_signal.c and task_exithook.c: Send signal to all
+ members for the parent task group.
+ * include/nuttx/sched.h and sched/env_*.c: Move environment
+ variables into task group structure.
+ * sched/: Lots of file changed. Don't keep the parent task's
+ task ID in the child task's TCB. Instead, keep the parent
+ task group IN the child task's task group.
+ * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h:
+ Move file data from the TCB to the task group structure.
+ * libc/stdio/, sched/, include/nuttx/lib.h, and include/nutts/fs/fs.h:
+ Move stream data from the TCB to the task group structure.
+ * net/, sched/, and include/nuttx/net/net.h: Move socket data
+ from the TCB to the task group structure.
+ * sched/task_starthook.c, sched/task_start.c, and include/nuttx/sched.h:
+ Add a task start hook that will be called before the task main
+ is started. This can be used to schedule C++ constructors to run
+ automatically in the context of the new task.
+ * binfmt/binfmt_execmodule: Execute constructors as a start hook.
+ * sched/os_start.c: Fix ordering of group initialization.
+ * configs/stm32f4discovery/usbnsh: Add an NSH STM32F4Discovery
+ configuration that uses USB CDC/ACM for the NSH console.
+ * configs/stm32f4discovery/nsh: Converted to use the kconfig-frontends
+ tools.
+ * configs/*/src/up_userleds.c: Fix a error that was cloned into
+ all STM32 user LED code. The wrong definitions were being used
+ to set LEDs on or off.
+ * arch/*/common/up_internal.h and arch/*/common/up_initialize.c:
+ Serial was driver was not being built if there is no console
+ device. Obviously, the serial driver may be needed even in
+ this case.
+ * arch/arm/src/stm32/stm32_serial.c: If there is a serial console,
+ it would be ttyS0 and the others would be ttyS1-5. If there
+ is not serial console, was labeling them ttyS1-6; now labels them
+ ttyS0-5.
+ * fs/fs_syslog.c: Can't handle SYSLOG output to character device from
+ the IDLE task (because it can't block). syslog_putc now returns EOF
+ on failure and sets errno. Fixed some errors in error handling.
+ * libc/stdio/lib_syslogstream.c: Checking of return value from
+ syslog_putc was bogus. Switching to EOF for all errors solves
+ this.
+ * arch/arm/src/lm/chip/lm4f_memorymap.h: More LM4F changes from
+ Jose Pablo Carballo.
+ * drivers/serial/serial.c, include/nuttx/serial/serial.h,
+ drivers/usbdev/cdcacm.c, and drivers/pl2303.c: Add support for
+ removable serial devices (like USB serial). This support is enabled
+ by CONFIG_SERIAL_REMOVABLE.
+ * arch/*/src/*/Toolchain.defs: Change assignment so that we can
+ override CROSSDEV with a make command line argument.
+ * include/assert.h: Mark assertion functions as non-returning.
+ * arch/*/src/*/up_assert.h: Mark _up_assert() as non-returning.
+ * drivers/mtd/at25.c: When the AT25 device was not available the
+ initialization did not fail like it should. From Petteri Aimonen.
+ * fs/fat/fs_configfat.c: Fix some errors in FAT formatting logic
+ for large devices and for FAT32. From Petteri Aimonen.
+ * fs/fat/fs_fat32util.c: Fix an initialization error found by
+ Petteri Aimonen. freecount and next freecount initialization were
+ reversed.
+ * drivers/mmcsd/mmcsd_spi.c: Some SD cards will appear busy until
+ switched to SPI mode for first time. Having a pull-up resistor on
+ MISO may avoid this problem, but this patch makes it work also
+ without pull-up. From Petteri Aimonen.
+ * fs/fat/fs_fat32.c: Fix a compilation error when FAT_DMAMEMORY=y.
+ From Petteri Aimonen.
+ * arch/arm/src/stm32/chip/stm32_spi.h: STM32F4 max SPI clock freq is
+ 37.5 MHz. Patch from Petteri Aimonen.
+ * arch/arm/src/stm32/stm32_spi.c: Fixes for SPI DMA work on the
+ STM32F4. Includes untested additions for the F1 implementation as
+ well. From Petteri Aimonen.
+
+6.26 2013-xx-xx Gregory Nutt <gnutt@nuttx.org>
+
+ * drivers/serial/serial.c: Correct some race conditions when checking
+ for disconnection of a removable serial device.
diff --git a/nuttx/Kconfig b/nuttx/Kconfig
index 10d624efb..af743b9db 100644
--- a/nuttx/Kconfig
+++ b/nuttx/Kconfig
@@ -297,26 +297,21 @@ config DEBUG
---help---
Enables built-in debug features. Selecting this option will (1) Enable
debug assertions in the code, (2) enable extended parameter testing in
- many functions, and (3) enable support for debug output. Note that enabling
- this option by itself does not produce debug output. Debug output must
- also be selected on a subsystem-by-subsystem basis.
+ many functions, and (3) enable support for debug output to the SYSLOG.
+ Note that enabling this option by itself does not produce debug output.
+ Debug output must also be selected on a subsystem-by-subsystem basis.
if DEBUG
config DEBUG_VERBOSE
bool "Enable Debug Verbose Output"
default n
---help---
- Enables verbose debug output (assuming debug output is enabled). As a
- general rule, when DEBUG is enabled only errors will be reported in the debug
- output. But if you also enable DEBUG_VERBOSE, then very chatty (and
- often annoying) output will be generated. This means there are two levels
- of debug output: errors-only and everything.
-
-config DEBUG_ENABLE
- bool "Enable Debug Controls"
- default n
- ---help---
- Support an interface to dynamically enable or disable debug output.
+ Enables verbose debug output (assuming debug featurses are enabled).
+ As a general rule, when DEBUG is enabled only errors will be
+ reported in the debug SYSLOG output. But if you also enable
+ DEBUG_VERBOSE, then very chatty (and often annoying) output will be
+ generated. This means there are two levels of debug output:
+ errors-only and everything.
comment "Subsystem Debug Options"
@@ -324,58 +319,58 @@ config DEBUG_MM
bool "Enable Memory Manager Debug Output"
default n
---help---
- Enable memory management debug output (disabled by default)
+ Enable memory management debug SYSLOG output (disabled by default)
config DEBUG_SCHED
bool "Enable Scheduler Debug Output"
default n
---help---
- Enable OS debug output (disabled by default)
+ Enable OS debug SYSLOG output (disabled by default)
config DEBUG_PAGING
bool "Enable Demand Paging Debug Output"
default n
depends on PAGING
---help---
- Enable demand paging debug output (disabled by default)
+ Enable demand paging debug SYSLOG output (disabled by default)
config DEBUG_NET
bool "Enable Network Debug Output"
default n
depends on NET
---help---
- Enable network debug output (disabled by default)
+ Enable network debug SYSLOG output (disabled by default)
config DEBUG_USB
bool "Enable USB Debug Output"
default n
depends on USBDEV || USBHOST
---help---
- Enable usb debug output (disabled by default)
+ Enable usb debug SYSLOG output (disabled by default)
config DEBUG_FS
bool "Enable File System Debug Output"
default n
---help---
- Enable file system debug output (disabled by default)
+ Enable file system debug SYSLOG output (disabled by default)
config DEBUG_LIB
bool "Enable C Library Debug Output"
default n
---help---
- Enable C library debug output (disabled by default)
+ Enable C library debug SYSLOG output (disabled by default)
config DEBUG_BINFMT
bool "Enable Binary Loader Debug Output"
default n
---help---
- Enable binary loader debug output (disabled by default)
+ Enable binary loader debug SYSLOG output (disabled by default)
config DEBUG_GRAPHICS
bool "Enable Graphics Debug Output"
default n
---help---
- Enable NX graphics debug output (disabled by default)
+ Enable NX graphics debug SYSLOG output (disabled by default)
comment "Driver Debug Options"
@@ -384,21 +379,21 @@ config DEBUG_LCD
default n
depends on LCD
---help---
- Enable low level debug output from the LCD driver (disabled by default)
+ Enable low level debug SYSLOG output from the LCD driver (disabled by default)
config DEBUG_INPUT
bool "Enable Input Device Debug Output"
default n
depends on INPUT
---help---
- Enable low level debug output from the input device drivers such as
+ Enable low level debug SYSLOG output from the input device drivers such as
mice and touchscreens (disabled by default)
config DEBUG_ANALOG
bool "Enable Analog Device Debug Output"
default n
---help---
- Enable low level debug output from the analog device drivers such as
+ Enable low level debug SYSLOG output from the analog device drivers such as
A/D and D/A converters (disabled by default)
config DEBUG_I2C
@@ -406,27 +401,27 @@ config DEBUG_I2C
default n
depends on I2C
---help---
- Enable I2C driver debug output (disabled by default)
+ Enable I2C driver debug SYSLOG output (disabled by default)
config DEBUG_SPI
bool "Enable SPI Debug Output"
default n
depends on SPI
---help---
- Enable I2C driver debug output (disabled by default)
+ Enable I2C driver debug SYSLOG output (disabled by default)
config DEBUG_DMA
bool "Enable DMA Debug Output"
default n
---help---
- Enable DMA-releated debug output (disabled by default)
+ Enable DMA-releated debug SYSLOG output (disabled by default)
config DEBUG_WATCHDOG
bool "Enable Watchdog Timer Debug Output"
default n
depends on WATCHDOG
---help---
- Enable watchdog timer debug output (disabled by default)
+ Enable watchdog timer debug SYSLOG output (disabled by default)
endif
diff --git a/nuttx/README.txt b/nuttx/README.txt
index 2ff473fa0..da1ed10c6 100644
--- a/nuttx/README.txt
+++ b/nuttx/README.txt
@@ -280,8 +280,14 @@ NuttX Configuration Tool
make menuconfig
- This make target will bring up NuttX configuration menus. The
- 'menuconfig' target depends on two things:
+ This make target will bring up NuttX configuration menus.
+
+ WARNING: Never do 'make menuconfig' on a configuration that has
+ not been converted to use the kconfig-frontends tools! This will
+ damage your configuration (see
+ http://www.nuttx.org/doku.php?id=wiki:howtos:convertconfig).
+
+ The 'menuconfig' make target depends on two things:
1. The Kconfig configuration data files that appear in almost all
NuttX directories. These data files are the part that is still
@@ -319,6 +325,22 @@ NuttX Configuration Tool
This is pretty straight forward for creating new configurations
but may be less intuitive for modifying existing configurations.
+Refreshing Configurations with 'make oldconfig'
+-----------------------------------------------
+
+ Whenever you use a configuration, you really should always do
+ the following *before* you make NuttX:
+
+ make oldconfig
+
+ This will make sure that the configuration is up-to-date in
+ the event that it has lapsed behind the current NuttX development.
+
+ WARNING: Never do 'make oldconfig' (OR 'make menuconfig') on a
+ configuration that has not been converted to use the kconfig-frontends
+ tools! This will damage your configuration (see
+ http://www.nuttx.org/doku.php?id=wiki:howtos:convertconfig).
+
Incompatibilities with Older Configurations
-------------------------------------------
@@ -501,8 +523,21 @@ NuttX Buildroot Toolchain
Disadvantages: This tool chain is not was well supported as some other
toolchains. GNU tools are not my priority and so the buildroot tools
- often get behind. For example, the is still no EABI support in the
- NuttX buildroot toolchain for ARM.
+ often get behind. For example, until recently there was no EABI support
+ in the NuttX buildroot toolchain for ARM.
+
+ NOTE: For Cortex-M3/4, there are OABI and EABI versions of the buildroot
+ toolchains. If you are using the older OABI toolchain the prefix for
+ the tools will be arm-nuttx-elf-; for the EABI toolchin the prefix will
+ be arm-nuttx-eabi-. If you are using the older OABI toolchain with
+ an ARM Cortex-M3/4, you will need to set CONFIG_ARMV7M_OABI_TOOLCHAIN
+ in the .config file in order to pick the right tool prefix.
+
+ If the make system ever picks the wrong prefix for your toolchain, you
+ can always specify the prefix on the command to override the default
+ like:
+
+ make CROSSDEV=arm-nuttx-elf
SHELLS
^^^^^^
@@ -1159,17 +1194,9 @@ apps
|- NxWidgets/
| `- README.txt
|- system/
- | |- i2c/README.txt
- | |- free/README.txt
- | |- install
- | | `- README.txt
- | |- poweroff
- | | `- README.txt
- | |- ramtron
- | | `- README.txt
- | |- sdcard
+ | |- i2c
| | `- README.txt
- | `- sysinfo
+ | `- install
| `- README.txt
`- README.txt
diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes
index 02cb8158d..4e8768b96 100644
--- a/nuttx/ReleaseNotes
+++ b/nuttx/ReleaseNotes
@@ -3440,3 +3440,323 @@ Bugfixes (see the change log for details). Some of these are very important
* Applications: Modbus fixes from Freddie Chopin.
As well as other, less critical bugs (see the ChangeLog for details)
+
+NuttX-6.25
+^^^^^^^^^^
+
+The 92nd release of NuttX, Version 6.25, was made on February 1, 2013,
+and is available for download from the SourceForge website. Note
+that release consists of two tarballs: nuttx-6.25.tar.gz and
+apps-6.25.tar.gz. Both may be needed (see the top-level nuttx/README.txt
+file for build information).
+
+This release corresponds with SVN release number: r5595
+
+Note that all SVN information has been stripped from the tarballs. If you
+need the SVN configuration information, you should check out directly from
+SVN. Revision r5595 should equivalent to release 6.25 of NuttX:
+
+ svn checkout -r5595 svn://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
+
+Or (HTTP):
+
+ svn checkout -r5595 http://svn.code.sf.net/p/nuttx/code/trunk nuttx-code
+
+Additional new features and extended functionality:
+
+ * OS Initialization
+
+ - Removed support for CONFIG_BUILTIN_APP_START. This is not really a
+ useful feature and creates a violation of the OS layered
+ architecture.
+
+ * Task Creation:
+
+ - Implement a simple vfork(). In NuttX-6.25, this interface is
+ available only for ARM7/9, ARMv7-M (Cortext-M3/4), and MIPS32
+ (PIC32MX) platforms.
+ - exec() now sets the priority of the new task to the same priority as
+ the parent task (instead of the arbirtrary value of 50).
+ - New, partially complient implementations of execv() and execl().
+ These are only partially compliant because they do not overlay any
+ existing "process space" but rather create the new task and exit().
+ - Add a complete implementation of posix_spawn(). This standard
+ interface is a better match for an MMU-less architecture than are
+ vfork() plus execv() or execl().
+ - Add a task start hook that will be called before the task main
+ is started. This can be used, for example, to schedule C++
+ static constructors to run automatically in the context of the
+ new task.
+
+ * Task Parentage
+
+ - Repartitioned tasking data structures. All shared resources are now
+ collected together in a "task group". A task group includes the
+ original task plus all of the pthreads created by the task.
+ - Added support for remember the parent "task group" when a new task is
+ started.
+ - Added optional support to record the membership of each thread in
+ the "task group".
+ - Implement support for retaining child task status in the "task group"
+ after the child task exists. This is behavior required by POSIX.
+ But in NuttX is only enabled with CONFIG_SCHED_HAVE_PARENT and
+ CONFIG_SCHED_CHILD_STATUS
+ - Add internal logic to "reparent" a task. This is useful,
+ for example, where the child task is created through a trampoline
+ task that redirects I/O. Reparenting allows the caller of posix_spawn()
+ to be reparented for the eventual child thread.
+ - Added support for SIGCHLD. Sent to all members of the parent task
+ group when the file member of the child task group exits.
+ - If SIGCHLD and retention of child task exist status are enabled, then
+ a more spec-compliant version of waitpid() is enabled.
+ - New interfaces waitid() and wait() are also enabled when SIGCHLD
+ is enabled.
+
+ * File System
+
+ - dup() and dup2() can new be used with opened files in a mounted file
+ system. This supports re-direction of output in NSH to files.
+ - The binfs file system was moved from apps/builtin to fs/binfs. The
+ binfs file system was extended to support execution of "builtin
+ applications" using exec(), execv(), execl(), or posix_spawn().
+ - Added logic based on SIGCHLD to automatically unload and clean-up
+ after running a task that was loaded into memory.
+
+ * Binary Formats
+
+ - Much of the logic for "builtin applications" was moved from
+ apps/builtin to nuttx/binfmt/libbuiltin. Includes some extensions
+ contributed by Mike Smith.
+ - A binary loader was added for builtin applications to support
+ execution of "builtin applications" using exec(), execv(),
+ execl(), or posix_spawn().
+
+ * Drivers:
+
+ - Added logic to marshal and serialized "out-of-band" keyboard
+ commands (such as cursor controls and key release events) intermixed
+ with normal ASCII keypress data. The encoding is partially integrated
+ in the HID keyboard driver and the decoding full integrated into the
+ apps/examples hidkbd and keypadtest (the latter contributed by Denis
+ Carlikli).
+ - Driver for the UG-2864HSWEG01 OLED contributed by Darcy Gong.
+ - Add support for removable serial devices (like USB serial). This
+ support is enabled by CONFIG_SERIAL_REMOVABLE.
+
+ * ARMv7-M:
+
+ - Added an option to use the BASEPRI register to disable interrupts
+ (instead of the PRIMASK). This eliminates some innocuous hardfaults
+ that interfere with some debug tools. You need to switch to the
+ BASEPRI method only if you have such tool interference.
+
+ * STM32 Drivers
+
+ - Bring STM32 F1 DMA capabilities up to par with the STM32 F2/F4
+ (contributed by Mike Smith).
+ - Add support for USART single wire mode (Contributed by the PX4
+ team).
+ - Updates to support for SPI DMA on the STM32 F1/F2/F4. From
+ Petteri Aimonen.
+
+ * STM32 Boards:
+
+ - New configuration to support the UG-2864HSWEG01 OLED on the
+ STM32F4Discovery board.
+ - Added a posix_spawn() test configuration for the STM32F4Discovery.
+
+ * LM3S/LM4F
+
+ - Files and directories repartitioned to support both LM3S and LM4F
+ using the STM32 organization as a model.
+ - Partial definitions for the LM4F contributed by Jose Pablo Carballo
+ (this is still a work in progress).
+
+ * LM3S Boards
+
+ - Added scripts and documentation to use OpenOCD with the LM3S (from
+ Jose Pablo Carballo).
+
+ * LPC176x/LPC178x
+
+ - Files and directories repartitioned to support both LPC175x/LPC176x
+ and the LPC177x/LPC178x families using the STM32 organization as a
+ model. The LPC1788 port is a work in progress by Rommel Marcelo.
+
+ * LPC176x/LPC178x Boards:
+
+ - Added a configuration to support the Wave Share Open1788 board.
+ This is still a work in progress by Rommel Marcelo.
+
+ * LPC2148 Boards:
+
+ - Add basic support for the The0.net ZP213x/4xPA board (with the LPC2148
+ and the UG_2864AMBAG01 OLED).
+ - Add an nxlines configuration for the ZP213x/4xPA (with the LPC2148
+ and the UG_2864AMBAG01).
+
+ * Simulator:
+
+ - Add an nxlines configuration for the simulator.
+
+ * Networking:
+
+ - Add logic to work around delayed ACKs by splitting packets
+ (contributed by Yan T.).
+ - Split net_poll() to create the internal interface psock_poll().
+
+ * LCDs:
+
+ - Added support for LCD1602 alphanumeric LCD (HD4468OU controller).
+
+ * Graphics:
+
+ - Added 5x8 monospace font. This tiny font is useful for graph
+ labels and for small bitmapped display. Contributed by Petteri
+ Aimonen.
+
+ * Build System:
+
+ - Add an options to better manage toolchain prefixes.
+ - Redesigned how the context targer works in the apps/ directory.
+ The old design caused lots of problems when changing configurations
+ because there is no easy way to get the system to rebuild the
+ context. This change should solve most the problems and eliminate
+ questions like "Why don't I see my builtin application in NSH?"
+
+ * Kconfig Files:
+
+ - There are several new configurations that use the kconfig-frontends
+ tools and several older configurations that have been converted to
+ use these tools. There is still a long way to go before the conversion
+ is complete:
+
+ configs/sim/nxwm
+ configs/sim/nsh
+ configs/stm3220g-eval/nxwm
+ configs/stm32f4discovery/posix_spawn
+ configs/olimex-lpc1766stk/nsh
+ configs/olimex-lpc1766stk/hidkbd
+ configs/olimex-lpc1766stk/nettest
+ configs/open1788/ostest
+ configs/stm32f4discovery/nsh
+ configs/stm32f4discovery/usbnsh
+ configs/lm326965-ek (all configurations)
+ configs/mcu123-214x/nsh
+ configs/ubw32/ostest
+
+ * Tools:
+
+ - tools/kconfig.bat: Kludge to run kconfig-frontends from a DOS shell.
+ - tools/configure.c: configure.c can be used to build a work-alike
+ program as a replacement for configure.sh. This work-alike
+ program would be used in environments that do not support Bash
+ scripting (such as the Windows native environment).
+ - tools/configure.bat: configure.bat is a small Windows batch
+ file that can be used as a replacement for configure.sh in a
+ Windows native environment. configure.bat is actually just a
+ thin layer that executes configure.exe if it is available. If
+ configure.exe is not available, then configure.bat will attempt
+ to build it first.
+
+ * Applications:
+
+ - New and modified examples:
+
+ apps/examples/wlan: Remove non-functional example.
+ apps/examples/ostest: Added a test of vfork(). Extend signal
+ handler test to catch death-of-child signals (SIGCHLD). Add a
+ test for waitpid(), waitid(), and wait().
+ apps/exampes/posix_spawn: Added a test of posix_spawn().
+
+ - NSH:
+
+ NSH now supports re-direction of I/O to files (but still not from).
+ The block driver source argument to the mount command is now
+ optional for file systems that do not require a block driver.
+ NSH can now execute a program from a file system using posix_spawn().
+ Added support for a login script. The init.d/rcS script will be
+ executed once when NSH starts; the .nshrc script will be executed
+ for each session: Once for serial, once for each USB connection,
+ once for each Telnet session.
+
+ - Supports a new daemon that can be used to monitor USB trace outpout.
+ - Removed non-functional wlan example.
+
+Bugfixes (see the ChangeLog for details). Some of these are very important:
+
+ * Tasking:
+
+ - Fixed a *critical* task exit bug. Here is the failure scenario:
+ (1) sched_lock() is called increments the lockcount on the current
+ TCB (i.e., the one at the head of the ready to run list), (2)
+ sched_mergepending is called which may change the task at the head
+ of the ready-to-run list, then (3) sched_unlock() is called which
+ decrements the lockcount on the wrong TCB. The failure case that
+ I saw was that pre-emption got disabled in the IDLE thread, locking
+ up the whole system.
+
+ * Signals:
+
+ - sigtimedwait() would return a bad signal number if the signal was
+ already pending when the function was called.
+
+ * Drivers:
+
+ - Some SD cards will appear busy until switched to SPI mode for
+ first time. Having a pull-up resistor on MISO may avoid this
+ problem, but this fix from Petteri Aimonen makes it work also
+ without pull-up.
+
+ * STM32 Drivers:
+
+ - STM32 FLASH driver counting error (from Freddie Chopin).
+ - STM32 F4 maximum SPI frequency was wrong (corrected by Petteri
+ Aimonen).
+
+ * STM32 Boards
+
+ - Due to cloning of untested code, the logic to control on-board
+ LEDs did not work on any STM32 boards.
+ - Serial devices number /dev/ttyS0-5 is there is a serial console,
+ but /dev/ttyS1-6 if there is no serial console.
+
+ * Binary Formats
+
+ - C++ static constructors execute now using a start taskhook
+ so that they execute in the context of the child task (instead
+ of in the context of the parent task).
+
+ * File Systems:
+
+ - Several FAT-related bugs fixed by Petteri Aimonen.
+
+ * Networking:
+
+ - Fix poll/select issure reported by Qiang: poll_interrupt() must call
+ net_lostconnection() when a loss of connection is reported. Otherwise,
+ the system will not remember that the connection has been lost and will
+ hang waiting on a unconnected socket later.
+ - Similar issues corrected for recvfrom() and send().
+ - Telnetd would hang in a loop if recv() ever returned a value <= 0.
+
+ * Libraries:
+
+ - fread() could hang on certain error conditions.
+ - Can't handle SYSLOG output to a character device from the IDLE task
+ (because the IDLE task can't block).
+
+ * Build System:
+
+ - Serial was driver was not being built if there is no console
+ device. Obviously, the serial driver may be needed even in
+ this case.
+
+ * Additional Bugfixes:
+
+ - sig_timedwait() and clock_time2ticks.c: Timing "rounding" logic
+ - ARM9 Compilation issue with low vectors.
+ - readline() return value
+ - Others as detailed in the ChangeLog: HID keyboard, LPC17xx bit
+ definitions, strndup(), PL2303, SYSLOG error handling, AT25,
+ apps/examples.
diff --git a/nuttx/TODO b/nuttx/TODO
index c302760ab..b5958f397 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -1,4 +1,4 @@
-NuttX TODO List (Last updated January 23, 2013)
+NuttX TODO List (Last updated January 30, 2013)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This file summarizes known NuttX bugs, limitations, inconsistencies with
@@ -7,14 +7,14 @@ standards, things that could be improved, and ideas for enhancements.
nuttx/
(11) Task/Scheduler (sched/)
- (1) Memory Managment (mm/)
+ (2) Memory Managment (mm/)
(3) Signals (sched/, arch/)
(2) pthreads (sched/)
(2) C++ Support
(6) Binary loaders (binfmt/)
- (17) Network (net/, drivers/net)
+ (16) Network (net/, drivers/net)
(4) USB (drivers/usbdev, drivers/usbhost)
- (12) Libraries (libc/, )
+ (11) Libraries (libc/, )
(9) File system/Generic drivers (fs/, drivers/)
(5) Graphics subystem (graphics/)
(1) Pascal add-on (pcode/)
@@ -161,25 +161,6 @@ o Task/Scheduler (sched/)
Status: Open
Priority: Medium Low for now
- Title: IMPROVED TASK CONTROL BLOCK STRUCTURE
- Description: All task resources that are shared amongst threads have
- their own "break-away", reference-counted structure. The
- Task Control Block (TCB) of each thread holds a reference
- to each breakaway structure (see include/nuttx/sched.h).
- It would be more efficent to have one reference counted
- structure that holds all of the shared resources.
-
- These are the current shared structures:
- - Environment varaibles (struct environ_s)
- - PIC data space and address environments (struct dspace_s)
- - File descriptors (struct filelist)
- - FILE streams (struct streamlist)
- - Sockets (struct socketlist)
- Status: Open
- Priority: Low. This is an enhancement. It would slight reduce
- memory usage but would also increase coupling. These
- resources are nicely modular now.
-
Title: ISSUES WITH atexit() AND on_exit()
Description: These functions execute with the following bad properties:
@@ -212,6 +193,16 @@ o Task/Scheduler (sched/)
Status: Open
Priority: Low (it might as well be low since it isn't going to be fixed).
+ Title: errno IS NOT SHARED AMONG THREADS
+ Description: In NuttX, the errno value is unique for each thread. But for
+ bug-for-bug compatibility, the same errno should be shared by
+ the task and each thread that it creates. It is *very* easy
+ to make this change: Just move the pterrno field from
+ _TCB to struct task_group_s. However, I am still not sure
+ if this should be done or not.
+ Status: Open
+ Priority: Low
+
o Memory Managment (mm/)
^^^^^^^^^^^^^^^^^^^^^^
@@ -278,6 +269,19 @@ o Memory Managment (mm/)
Priority: Medium/Low, a good feature to prevent memory leaks but would
have negative impact on memory usage and code size.
+ Title: CONTAINER ALLOCATOR
+ Description: There are several places where the logic requires allocation of
+ a tiny structure that just contains pointers to other things or
+ small amounts of data that needs to be bundled together. There
+ are examples net/net_poll.c and numerous other places.
+
+ I am wondering if it would not be good create a pool of generic
+ containers (say void *[4]). There re-use these when we need
+ small containers. The code in sched/task_childstatus.c might
+ be generalized for this purpose.
+ Status: Open
+ Priority: Very low (I am not even sure that this is a good idea yet).
+
o Signals (sched/, arch/)
^^^^^^^^^^^^^^^^^^^^^^^
@@ -413,6 +417,9 @@ o Binary loaders (binfmt/)
Description: Not all of the NXFLAT test under apps/examples/nxflat are working.
Most simply do not compile yet. tests/mutex runs okay but
outputs garbage on completion.
+
+ Update: 13-27-1, tests/mutex crashed with a memory corruption
+ problem the last time that I ran it.
Status: Open
Priority: High
@@ -667,21 +674,6 @@ o Network (net/, drivers/net)
Status: Open
Priority: Low... fix defconfig files as necessary.
- Title: net_poll() DOES NOT HANDLE LOSS-OF-CONNECTION CORRECTLY
- Description: When a loss of connection is detected by any logic waiting on the
- networking events, the function net_lostconnection() must be called.
- That function just sets some bits in the socket structure so that
- it remembers that the connection is lost.
-
- That is currently done in recvfrom(), send(), and net_monitor.c. But
- it is not done in the net_poll() logic; that logic correctly sets
- the POLLHUP status, but it does not call net_lostconnection(). As a
- result, if recv() is called after the poll() or select(), the system
- will hang because the recv() does not know that the connection has
- been lost.
- Status: Open
- Priority: High
-
o USB (drivers/usbdev, drivers/usbhost)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
@@ -820,19 +812,6 @@ o Libraries (libc/)
Status: Open
Priority: ??
- Title: SYSLOG INTEGRATION
- Description: There are the beginnings of some system logging capabilities (see
- drivers/syslog, fs/fs_syslog.c, and libc/stdio/lib_librawprintf.c and
- lib_liblowprintf.c. For NuttX, SYSLOG is a concept and includes,
- extends, and replaces the legacy NuttX debug ouput. Some additional
- integration is required to formalized this. For example:
-
- o lib_rawprintf() shjould be renamed syslog().
- o debug.h should be renamed syslog.h
- o And what about lib_lowprintf()? llsyslog?
- Status: Open
- Priority: Low -- more of a roadmap
-
Title: FLOATING POINT FORMATS
Description: Only the %f floating point format is supported. Others are accepted
but treated like %f.
@@ -1526,11 +1505,6 @@ o ARM/STM32 (arch/arm/src/stm32/)
Status: Open
Priority: Low
- Title: STM32 F4 USB OTG FS DEVICE-SIDE DRIVER
- Description: This driver is reported to be buggy and to need some TLC.
- Status: Open
- Priority: High
-
o AVR (arch/avr)
^^^^^^^^^^^^^^
diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
index 45ee9e36c..4de5b49f4 100644
--- a/nuttx/arch/arm/src/armv7-m/Toolchain.defs
+++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
@@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/armv7-m/Toolchain.defs
#
-# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -141,8 +141,8 @@ endif
# Atollic toolchain under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC)
- CROSSDEV = arm-atollic-eabi-
- ARCROSSDEV = arm-atollic-eabi-
+ CROSSDEV ?= arm-atollic-eabi-
+ ARCROSSDEV ?= arm-atollic-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -161,12 +161,12 @@ endif
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT)
ifeq ($(CONFIG_ARMV7M_OABI_TOOLCHAIN),y)
- CROSSDEV = arm-nuttx-elf-
- ARCROSSDEV = arm-nuttx-elf-
+ CROSSDEV ?= arm-nuttx-elf-
+ ARCROSSDEV ?= arm-nuttx-elf-
ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
else
- CROSSDEV = arm-nuttx-eabi-
- ARCROSSDEV = arm-nuttx-eabi-
+ CROSSDEV ?= arm-nuttx-eabi-
+ ARCROSSDEV ?= arm-nuttx-eabi-
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
endif
MAXOPTIMIZATION = -Os
@@ -175,8 +175,8 @@ endif
# Code Red RedSuite under Linux
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDL)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifeq ($(CONFIG_ARCH_CORTEXM4),y)
ifeq ($(CONFIG_ARCH_FPU),y)
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
@@ -191,8 +191,8 @@ endif
# Code Red RedSuite under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -210,8 +210,8 @@ endif
# CodeSourcery under Linux
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYL)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
MAXOPTIMIZATION = -O2
endif
@@ -219,8 +219,8 @@ endif
# CodeSourcery under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -230,8 +230,8 @@ endif
# devkitARM under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM)
- CROSSDEV = arm-eabi-
- ARCROSSDEV = arm-eabi-
+ CROSSDEV ?= arm-eabi-
+ ARCROSSDEV ?= arm-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
@@ -241,8 +241,8 @@ endif
# Generic GNU EABI toolchain on OS X, Linux or any typical Posix system
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
MAXOPTIMIZATION = -O3
ifeq ($(CONFIG_ARCH_CORTEXM4),y)
ifeq ($(CONFIG_ARCH_FPU),y)
@@ -258,8 +258,8 @@ endif
# Raisonance RIDE7 under Windows
ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE)
- CROSSDEV = arm-none-eabi-
- ARCROSSDEV = arm-none-eabi-
+ CROSSDEV ?= arm-none-eabi-
+ ARCROSSDEV ?= arm-none-eabi-
ifneq ($(CONFIG_WINDOWS_NATIVE),y)
WINTOOL = y
endif
diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c
index ab30b09f3..b40b1090c 100644
--- a/nuttx/arch/arm/src/armv7-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv7-m/up_assert.c
@@ -62,7 +62,7 @@
#ifdef CONFIG_ARCH_STACKDUMP
# undef lldbg
-# define lldbg lib_lowprintf
+# define lldbg lowsyslog
#endif
/* The following is just intended to keep some ugliness out of the mainline
@@ -70,7 +70,7 @@
*
* CONFIG_TASK_NAME_SIZE > 0 && <-- The task has a name
* (defined(CONFIG_DEBUG) || <-- And the debug is enabled (lldbg used)
- * defined(CONFIG_ARCH_STACKDUMP) <-- Or lib_lowprintf() is used
+ * defined(CONFIG_ARCH_STACKDUMP) <-- Or lowsyslog() is used
*/
#undef CONFIG_PRINT_TASKNAME
@@ -267,7 +267,8 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* noreturn_function */
+static void _up_assert(int errorcode) noreturn_function;
+static void _up_assert(int errorcode)
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
index f1c961b15..9a971f064 100644
--- a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
+++ b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_reprioritizertr.c
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c
index 6f6d54f76..16f5c4442 100644
--- a/nuttx/arch/arm/src/common/up_exit.c
+++ b/nuttx/arch/arm/src/common/up_exit.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_exit.c
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 201-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -75,7 +75,11 @@
#if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG)
static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
{
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ FAR struct filelist *filelist;
+#if CONFIG_NFILE_STREAMS > 0
+ FAR struct streamlist *streamlist;
+#endif
int i;
#endif
@@ -83,42 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state);
#if CONFIG_NFILE_DESCRIPTORS > 0
- if (tcb->filelist)
+ filelist = tcb->group->tg_filelist;
+ for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
{
- sdbg(" filelist refcount=%d\n",
- tcb->filelist->fl_crefs);
-
- for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
+ struct inode *inode = filelist->fl_files[i].f_inode;
+ if (inode)
{
- struct inode *inode = tcb->filelist->fl_files[i].f_inode;
- if (inode)
- {
- sdbg(" fd=%d refcount=%d\n",
- i, inode->i_crefs);
- }
+ sdbg(" fd=%d refcount=%d\n",
+ i, inode->i_crefs);
}
}
#endif
#if CONFIG_NFILE_STREAMS > 0
- if (tcb->streams)
+ streamlist = tcb->group->tg_streamlist;
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
{
- sdbg(" streamlist refcount=%d\n",
- tcb->streams->sl_crefs);
-
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ struct file_struct *filep = &streamlist->sl_streams[i];
+ if (filep->fs_filedes >= 0)
{
- struct file_struct *filep = &tcb->streams->sl_streams[i];
- if (filep->fs_filedes >= 0)
- {
#if CONFIG_STDIO_BUFFER_SIZE > 0
- sdbg(" fd=%d nbytes=%d\n",
- filep->fs_filedes,
- filep->fs_bufpos - filep->fs_bufstart);
+ sdbg(" fd=%d nbytes=%d\n",
+ filep->fs_filedes,
+ filep->fs_bufpos - filep->fs_bufstart);
#else
- sdbg(" fd=%d\n", filep->fs_filedes);
+ sdbg(" fd=%d\n", filep->fs_filedes);
#endif
- }
}
}
#endif
diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c
index 80f9b1193..0ea3fcd35 100644
--- a/nuttx/arch/arm/src/common/up_initialize.c
+++ b/nuttx/arch/arm/src/common/up_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/common/up_initialize.c
*
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -161,11 +161,17 @@ void up_initialize(void)
devnull_register(); /* Standard /dev/null */
#endif
- /* Initialize the console device driver */
+ /* Initialize the serial device driver */
-#if defined(USE_SERIALDRIVER)
+#ifdef USE_SERIALDRIVER
up_serialinit();
-#elif defined(CONFIG_DEV_LOWCONSOLE)
+#endif
+
+ /* Initialize the console device driver (if it is other than the standard
+ * serial driver).
+ */
+
+#if defined(CONFIG_DEV_LOWCONSOLE)
lowconsole_init();
#elif defined(CONFIG_RAMLOG_CONSOLE)
ramlog_consoleinit();
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 55071345f..8a24f003e 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_internal.h
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -63,7 +63,10 @@
#undef CONFIG_SUPPRESS_UART_CONFIG /* DEFINED: Do not reconfig UART */
#undef CONFIG_DUMP_ON_EXIT /* DEFINED: Dump task state on exit */
-/* Determine which (if any) console driver to use */
+/* Determine which (if any) console driver to use. If a console is enabled
+ * and no other console device is specified, then a serial console is
+ * assumed.
+ */
#if !defined(CONFIG_DEV_CONSOLE) || CONFIG_NFILE_DESCRIPTORS == 0
# undef USE_SERIALDRIVER
@@ -84,6 +87,16 @@
# endif
#endif
+/* If some other device is used as the console, then the serial driver may
+ * still be needed. Let's assume that if the upper half serial driver is
+ * built, then the lower half will also be needed. There is no need for
+ * the early serial initialization in this case.
+ */
+
+#if !defined(USE_SERIALDRIVER) && defined(CONFIG_STANDARD_SERIAL)
+# define USE_SERIALDRIVER 1
+#endif
+
/* Determine which device to use as the system logging device */
#ifndef CONFIG_SYSLOG
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_spi.h b/nuttx/arch/arm/src/stm32/chip/stm32_spi.h
index d80c447bb..7731d03b0 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_spi.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_spi.h
@@ -47,7 +47,13 @@
* Pre-processor Definitions
************************************************************************************/
-#define STM32_SPI_CLK_MAX 18000000UL /* Maximum allowed speed as per specifications for all SPIs */
+/* Maximum allowed speed as per specifications for all SPIs */
+
+#if defined(CONFIG_STM32_STM32F40XX)
+# define STM32_SPI_CLK_MAX 37500000UL
+#else
+# define STM32_SPI_CLK_MAX 18000000UL
+#endif
/* Register Offsets *****************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.c b/nuttx/arch/arm/src/stm32/stm32_adc.c
index 844f1fd0f..b5033b057 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.c
@@ -118,25 +118,12 @@ struct stm32_dev_s
uint32_t freq; /* The desired frequency of conversions */
#endif
uint8_t chanlist[ADC_MAX_SAMPLES];
-#ifdef CONFIG_ADC_DMA
- const unsigned int rxdma_channel; /* DMA channel assigned */
- DMA_HANDLE rxdma; /* currently-open receive DMA stream */
- bool rxenable; /* DMA-based reception en/disable */
- uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */
- int32_t *const rxfifo; /* Receive DMA buffer */
-#endif
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-# ifdef CONFIG_ADC_DMA
-static int16_t g_adc3dmarxfifo[ADC_MAX_SAMPLES];
-# endif
-
-
-
/* ADC Register access */
static uint32_t adc_getreg(struct stm32_dev_s *priv, int offset);
@@ -179,15 +166,6 @@ static int adc_timinit(FAR struct stm32_dev_s *priv);
static void adc_startconv(FAR struct stm32_dev_s *priv, bool enable);
#endif
-#ifdef CONFIG_ADC_DMA
-static int up_dma_setup(struct adc_dev_s *dev);
-static void up_dma_shutdown(struct adc_dev_s *dev);
-//static int up_dma_receive(struct uart_dev_s *dev, uint32_t *status);
-//static void up_dma_rxint(struct uart_dev_s *dev, bool enable);
-//static bool up_dma_rxavailable(struct uart_dev_s *dev);
-static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, FAR struct adc_dev_s *dev);
-#endif
-
/****************************************************************************
* Private Data
****************************************************************************/
@@ -284,10 +262,6 @@ static struct stm32_dev_s g_adcpriv3 =
.pclck = ADC3_TIMER_PCLK_FREQUENCY,
.freq = CONFIG_STM32_ADC3_SAMPLE_FREQUENCY,
#endif
-#ifdef CONFIG_ADC_DMA
- .rxdma_channel = DMAMAP_ADC3_2,
- .rxfifo = g_adc3dmarxfifo,
-#endif
};
static struct adc_dev_s g_adcdev3 =
@@ -569,7 +543,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
* So ( prescaler = pclck / 65535 / freq ) would be optimal.
*/
- prescaler = 128;//(priv->pclck / priv->freq + 65534) / 65535;
+ prescaler = (priv->pclck / priv->freq + 65534) / 65535;
/* We need to decrement the prescaler value by one, but only, the value does
* not underflow.
@@ -591,7 +565,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
timclk = priv->pclck / prescaler;
- reload = priv->freq;//timclk / priv->freq;
+ reload = timclk / priv->freq;
if (reload < 1)
{
adbg("WARNING: Reload value underflowed.\n");
@@ -720,10 +694,10 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
case 4: /* TimerX TRGO event */
{
-#warning "TRGO support not yet implemented"
-
+ /* TODO: TRGO support not yet implemented */
/* Set the event TRGO */
+ ccenable = 0;
egr = GTIM_EGR_TG;
/* Set the duty cycle by writing to the CCR register for this channel */
@@ -936,139 +910,6 @@ static void adc_rccreset(struct stm32_dev_s *priv, bool reset)
irqrestore(flags);
}
-/****************************************************************************
- * Name: up_dma_setup
- *
- * Description:
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADC_DMA
-static int up_dma_setup(FAR struct adc_dev_s *dev)
-{
-
- FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
- int result;
- uint32_t regval;
-
-//
-// result = up_setup(dev);
-// if (result != OK)
-// {
-// return result;
-// }
-
- /* Acquire the DMA channel. This should always succeed. */
-
- priv->rxdma = stm32_dmachannel(priv->rxdma_channel);
-
- /* Configure for circular DMA reception into the RX fifo */
-
- stm32_dmasetup(priv->rxdma,
- priv->base + STM32_ADC_DR_OFFSET,
- (uint32_t)priv->rxfifo,
- 4,//buffersize
- DMA_SCR_DIR_P2M |
- DMA_SCR_CIRC |
- DMA_SCR_MINC |
- DMA_SCR_PSIZE_16BITS |
- DMA_SCR_MSIZE_16BITS |
- DMA_SCR_PBURST_SINGLE |
- DMA_SCR_MBURST_SINGLE);
-
- /* Reset our DMA shadow pointer to match the address just
- * programmed above.
- */
-
- //priv->rxdmanext = 0;
-
- /* Enable DMA for the ADC */
-
- /* Start the DMA channel, and arrange for callbacks at the half and
- * full points in the FIFO. This ensures that we have half a FIFO
- * worth of time to claim bytes before they are overwritten.
- */
-
- stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)dev, false);
-
- return OK;
-}
-#endif
-/****************************************************************************
- * Name: up_dma_rxcallback
- *
- * Description:
-
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADC_DMA
-static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, FAR struct adc_dev_s *dev)
-{
- //struct up_dev_s *priv = (struct up_dev_s*)arg;
- //uint32_t regval;
- FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
- //struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
-
- //if (priv->rxenable && up_dma_rxavailable(&priv->dev))
- {
- /* Give the ADC data to the ADC driver. adc_receive accepts 3 parameters:
- *
- * 1) The first is the ADC device instance for this ADC block.
- * 2) The second is the channel number for the data, and
- * 3) The third is the converted data for the channel.
- */
-
-
- adc_receive(dev, 10, (int32_t)g_adc3dmarxfifo[1]);
- adc_receive(dev, 11, (int32_t)g_adc3dmarxfifo[2]);
- adc_receive(dev, 12, (int32_t)g_adc3dmarxfifo[3]);
- adc_receive(dev, 13, (int32_t)g_adc3dmarxfifo[0]);
-
-
- /* Set the channel number of the next channel that will complete conversion */
-
- priv->current++;
-
- if (priv->current >= priv->nchannels)
- {
- /* Restart the conversion sequence from the beginning */
-
- priv->current = 0;
- }
-
-
- }
-}
-#endif
-
-/****************************************************************************
- * Name: up_dma_shutdown
- *
- * Description:
- * Disable the DMA
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ADC_DMA
-static void up_dma_shutdown(struct adc_dev_s *dev)
-{
-
- FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
-
-
- /* Stop the DMA channel */
-
- stm32_dmastop(priv->rxdma);
-
- /* Release the DMA channel */
-
- stm32_dmafree(priv->rxdma);
- priv->rxdma = NULL;
-}
-#endif
-
-
/*******************************************************************************
* Name: adc_enable
*
@@ -1089,7 +930,7 @@ static void adc_enable(FAR struct stm32_dev_s *priv, bool enable)
{
uint32_t regval;
- // avdbg("enable: %d\n", enable);
+ avdbg("enable: %d\n", enable);
regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
if (enable)
@@ -1123,12 +964,14 @@ static void adc_reset(FAR struct adc_dev_s *dev)
uint32_t regval;
int offset;
int i;
+#ifdef ADC_HAVE_TIMER
int ret;
+#endif
avdbg("intf: ADC%d\n", priv->intf);
flags = irqsave();
- /* Enable ADC reset state */
+ /* Enable ADC reset state */
adc_rccreset(priv, true);
@@ -1146,7 +989,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
adc_putreg(priv, STM32_ADC_LTR_OFFSET, 0x00000000);
-
/* Initialize the same sample time for each ADC 55.5 cycles
*
* During sample cycles channel selection bits must remain unchanged.
@@ -1179,8 +1021,16 @@ static void adc_reset(FAR struct adc_dev_s *dev)
regval |= ADC_CR1_AWDEN;
regval |= (priv->chanlist[0] << ADC_CR1_AWDCH_SHIFT);
+ /* Enable interrupt flags */
+
+ regval |= ADC_CR1_ALLINTS;
+
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+ /* Enable or disable Overrun interrupt */
+
+ regval &= ~ADC_CR1_OVRIE;
+
/* Set the resolution of the conversion */
regval |= ACD_CR1_RES_12BIT;
@@ -1229,12 +1079,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
{
regval |= (uint32_t)priv->chanlist[i] << offset;
}
- /* Set the number of conversions */
-
- DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES);
-
- regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT);
- adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval);
/* ADC CCR configuration */
@@ -1246,7 +1090,12 @@ static void adc_reset(FAR struct adc_dev_s *dev)
putreg32(regval, STM32_ADC_CCR);
#endif
+ /* Set the number of conversions */
+ DEBUGASSERT(priv->nchannels <= ADC_MAX_SAMPLES);
+
+ regval |= (((uint32_t)priv->nchannels-1) << ADC_SQR1_L_SHIFT);
+ adc_putreg(priv, STM32_ADC_SQR1_OFFSET, regval);
/* Set the channel index of the first conversion */
@@ -1270,29 +1119,24 @@ static void adc_reset(FAR struct adc_dev_s *dev)
adc_enable(priv, true);
#else
-#ifdef CONFIG_ADC_DMA
- //nothing
-#else
adc_startconv(priv, true);
-#endif
#endif /* CONFIG_STM32_STM32F10XX */
#endif /* ADC_HAVE_TIMER */
-
irqrestore(flags);
-// avdbg("SR: 0x%08x CR1: 0x%08x CR2: 0x%08x\n",
-// adc_getreg(priv, STM32_ADC_SR_OFFSET),
-// adc_getreg(priv, STM32_ADC_CR1_OFFSET),
-// adc_getreg(priv, STM32_ADC_CR2_OFFSET));
-// avdbg("SQR1: 0x%08x SQR2: 0x%08x SQR3: 0x%08x\n",
-// adc_getreg(priv, STM32_ADC_SQR1_OFFSET),
-// adc_getreg(priv, STM32_ADC_SQR2_OFFSET),
-// adc_getreg(priv, STM32_ADC_SQR3_OFFSET));
-//#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
-// avdbg("CCR: 0x%08x\n",
-// getreg32(STM32_ADC_CCR));
-//#endif
+ avdbg("SR: 0x%08x CR1: 0x%08x CR2: 0x%08x\n",
+ adc_getreg(priv, STM32_ADC_SR_OFFSET),
+ adc_getreg(priv, STM32_ADC_CR1_OFFSET),
+ adc_getreg(priv, STM32_ADC_CR2_OFFSET));
+ avdbg("SQR1: 0x%08x SQR2: 0x%08x SQR3: 0x%08x\n",
+ adc_getreg(priv, STM32_ADC_SQR1_OFFSET),
+ adc_getreg(priv, STM32_ADC_SQR2_OFFSET),
+ adc_getreg(priv, STM32_ADC_SQR3_OFFSET));
+#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+ avdbg("CCR: 0x%08x\n",
+ getreg32(STM32_ADC_CCR));
+#endif
}
/****************************************************************************
@@ -1314,86 +1158,21 @@ static int adc_setup(FAR struct adc_dev_s *dev)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
int ret;
- uint32_t regval;
-
-
- /* the adc seems to need a full reset to be enabled correctly */
- adc_reset(dev);
-#ifndef CONFIG_ADC_DMA
/* Attach the ADC interrupt */
ret = irq_attach(priv->irq, priv->isr);
if (ret == OK)
{
+ /* Make sure that the ADC device is in the powered up, reset state */
+
+ adc_reset(dev);
+
/* Enable the ADC interrupt */
avdbg("Enable the ADC interrupt: irq=%d\n", priv->irq);
up_enable_irq(priv->irq);
}
-#endif
-
-#ifdef CONFIG_ADC_DMA
- up_dma_setup(dev);
-
-
-//#ifndef ADC_HAVE_TIMER
-// /*disable external trigger*/
-// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
-// regval |= ACD_CR2_EXTEN_NONE;
-// //regval |= ADC_CR1_DISCEN;
-// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-//#else
-// /*enable external trigger*/
-// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
-// regval |=ADC_CR2_EXTSEL_T4CC4;
-// regval |=ACD_CR2_EXTEN_BOTH;
-// //regval |= ADC_CR2_CONT;
-// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-//#endif
-
-
- /*enable scan mode*/
- regval = adc_getreg(priv, STM32_ADC_CR1_OFFSET);
- regval |= ADC_CR1_SCAN;
- //regval |= ADC_CR1_DISCEN;
- adc_putreg(priv, STM32_ADC_CR1_OFFSET, regval);
-
- /* Enable DMA request after last transfer (Single-ADC mode) */
- //ADC_DMARequestAfterLastTransferCmd(ADC3, ENABLE);
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_DDS;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-
- /* Enable ADC3 DMA */
- // ADC_DMACmd(ADC3, ENABLE);
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_DMA;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-#endif
-
-
-#ifndef ADC_HAVE_TIMER
- /*set continuous conversion */
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_CONT;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-#endif
-
- /* Enable ADC3 */
- //ADC_Cmd(ADC3, ENABLE);
- regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
- regval |= ADC_CR2_ADON;
- adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-
-//// /*start conversion*/
-// regval = adc_getreg(priv, STM32_ADC_CR2_OFFSET);
-// regval |= ADC_CR2_SWSTART;
-// adc_putreg(priv, STM32_ADC_CR2_OFFSET, regval);
-
-
-
-
return ret;
}
@@ -1415,24 +1194,14 @@ static void adc_shutdown(FAR struct adc_dev_s *dev)
{
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev->ad_priv;
-#ifdef CONFIG_ADC_DMA
- up_dma_shutdown(dev);
-#endif
-
-#ifdef ADC_HAVE_TIMER
- /* stop adc timer */
- adc_timstart(priv, false);
-#endif
+ /* Disable ADC interrupts and detach the ADC interrupt handler */
- /* power down ADC */
- adc_enable(priv, false);
+ up_disable_irq(priv->irq);
+ irq_detach(priv->irq);
- adc_rxint(dev, false);
+ /* Disable and reset the ADC module */
- /* Disable ADC interrupts and detach the ADC interrupt handler */
- up_disable_irq(priv->irq);
-// irq_detach(priv->irq);
- // XXX Why is irq_detach here commented out?
+ adc_rccreset(priv, true);
}
/****************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h
index 7b6c13b33..060fcdfb9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.h
@@ -161,6 +161,12 @@
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+/* DMA support is not yet implemented for this driver */
+
+#ifdef CONFIG_ADC_DMA
+# warning "DMA is not supported by the current driver"
+#endif
+
/* Timer configuration: If a timer trigger is specified, then get information
* about the timer.
*/
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index a4b10b55c..82ae6af5f 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -107,11 +107,11 @@
#if !defined(CONFIG_STM32_I2CTIMEOSEC) && !defined(CONFIG_STM32_I2CTIMEOMS)
# define CONFIG_STM32_I2CTIMEOSEC 0
-# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
+# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOSEC)
# define CONFIG_STM32_I2CTIMEOSEC 0 /* User provided milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOMS)
-# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
+# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
#endif
/* Interrupt wait time timeout in system timer ticks */
@@ -141,7 +141,7 @@
#endif
/* I2C event trace logic. NOTE: trace uses the internal, non-standard, low-level
- * debug interface lib_rawprintf() but does not require that any other debug
+ * debug interface syslog() but does not require that any other debug
* is enabled.
*/
@@ -219,31 +219,31 @@ struct stm32_i2c_config_s
struct stm32_i2c_priv_s
{
const struct stm32_i2c_config_s *config; /* Port configuration */
- int refs; /* Referernce count */
- sem_t sem_excl; /* Mutual exclusion semaphore */
+ int refs; /* Referernce count */
+ sem_t sem_excl; /* Mutual exclusion semaphore */
#ifndef CONFIG_I2C_POLLED
- sem_t sem_isr; /* Interrupt wait semaphore */
+ sem_t sem_isr; /* Interrupt wait semaphore */
#endif
- volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
+ volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
- uint8_t msgc; /* Message count */
- struct i2c_msg_s *msgv; /* Message list */
- uint8_t *ptr; /* Current message buffer */
- int dcnt; /* Current message length */
- uint16_t flags; /* Current message flags */
+ uint8_t msgc; /* Message count */
+ struct i2c_msg_s *msgv; /* Message list */
+ uint8_t *ptr; /* Current message buffer */
+ int dcnt; /* Current message length */
+ uint16_t flags; /* Current message flags */
/* I2C trace support */
#ifdef CONFIG_I2C_TRACE
- int tndx; /* Trace array index */
- uint32_t start_time; /* Time when the trace was started */
+ int tndx; /* Trace array index */
+ uint32_t start_time; /* Time when the trace was started */
/* The actual trace data */
struct stm32_trace_s trace[CONFIG_I2C_NTRACE];
#endif
- uint32_t status; /* End of transfer SR2|SR1 status */
+ uint32_t status; /* End of transfer SR2|SR1 status */
};
/* I2C Device, Instance */
@@ -281,7 +281,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu
static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
enum stm32_trace_e event, uint32_t parm);
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
-#endif
+#endif /* CONFIG_I2C_TRACE */
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
uint32_t frequency);
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
@@ -291,7 +291,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv);
#ifdef I2C1_FSMC_CONFLICT
static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_enablefsmc(uint32_t ahbenr);
-#endif
+#endif /* I2C1_FSMC_CONFLICT */
static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv);
#ifndef CONFIG_I2C_POLLED
#ifdef CONFIG_STM32_I2C1
@@ -582,15 +582,14 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int
abstime.tv_sec++;
abstime.tv_nsec -= 1000 * 1000 * 1000;
}
-#else
- #if CONFIG_STM32_I2CTIMEOMS > 0
- abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
- if (abstime.tv_nsec > 1000 * 1000 * 1000)
- {
- abstime.tv_sec++;
- abstime.tv_nsec -= 1000 * 1000 * 1000;
- }
- #endif
+
+#elif CONFIG_STM32_I2CTIMEOMS > 0
+ abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
+ if (abstime.tv_nsec > 1000 * 1000 * 1000)
+ {
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000 * 1000 * 1000;
+ }
#endif
/* Wait until either the transfer is complete or the timeout expires */
@@ -866,11 +865,11 @@ static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv)
struct stm32_trace_s *trace;
int i;
- lib_rawprintf("Elapsed time: %d\n", clock_systimer() - priv->start_time);
+ syslog("Elapsed time: %d\n", clock_systimer() - priv->start_time);
for (i = 0; i <= priv->tndx; i++)
{
trace = &priv->trace[i];
- lib_rawprintf("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n",
+ syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n",
i+1, trace->status, trace->count, trace->event, trace->parm,
trace->time - priv->start_time);
}
@@ -932,7 +931,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
{
/* Fast mode speed calculation with Tlow/Thigh = 16/9 */
-#ifdef CONFIG_I2C_DUTY16_9
+#ifdef CONFIG_STM32_I2C_DUTY16_9
speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
/* Set DUTY and fast speed bits */
@@ -1071,7 +1070,7 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv)
/* Is this I2C1 */
-#ifdef CONFIG_STM32_I2C2
+#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3)
if (priv->config->base == STM32_I2C1_BASE)
#endif
{
@@ -1198,26 +1197,29 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
{
stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt);
+ /* No interrupts or context switches may occur in the following
+ * sequence. Otherwise, additional bytes may be sent by the
+ * device.
+ */
+
#ifdef CONFIG_I2C_POLLED
irqstate_t state = irqsave();
#endif
-
/* Receive a byte */
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
/* Disable acknowledge when last byte is to be received */
+ priv->dcnt--;
if (priv->dcnt == 1)
{
stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0);
}
- priv->dcnt--;
#ifdef CONFIG_I2C_POLLED
irqrestore(state);
#endif
-
}
}
@@ -1408,7 +1410,6 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Enable power and reset the peripheral */
modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit);
-
modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit);
modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0);
@@ -1428,10 +1429,10 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Attach ISRs */
#ifndef CONFIG_I2C_POLLED
- irq_attach(priv->config->ev_irq, priv->config->isr);
- irq_attach(priv->config->er_irq, priv->config->isr);
- up_enable_irq(priv->config->ev_irq);
- up_enable_irq(priv->config->er_irq);
+ irq_attach(priv->config->ev_irq, priv->config->isr);
+ irq_attach(priv->config->er_irq, priv->config->isr);
+ up_enable_irq(priv->config->ev_irq);
+ up_enable_irq(priv->config->er_irq);
#endif
/* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz
@@ -1461,17 +1462,23 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv)
stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0);
+ /* Unconfigure GPIO pins */
+
stm32_unconfiggpio(priv->config->scl_pin);
stm32_unconfiggpio(priv->config->sda_pin);
+ /* Disable and detach interrupts */
+
#ifndef CONFIG_I2C_POLLED
up_disable_irq(priv->config->ev_irq);
up_disable_irq(priv->config->er_irq);
irq_detach(priv->config->ev_irq);
irq_detach(priv->config->er_irq);
#endif
- modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
+ /* Disable clocking */
+
+ modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
return OK;
}
@@ -1623,7 +1630,9 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/
stm32_i2c_clrstart(priv);
- // XXX also clear busy flag in case of timeout
+
+ /* Clear busy flag in case of timeout */
+
status = priv->status & 0xffff;
}
else
@@ -2070,4 +2079,4 @@ out:
return ret;
}
-#endif /* defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) */
+#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 94772b693..bcce3ce60 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -146,15 +146,6 @@
# error "CONFIG_USBDEV_EP3_TXFIFO_SIZE is out of range"
#endif
-/* REVISIT! This forces a hack that polls DTXFSTS for space in the Tx FIFO.
- * Enabling this option is a BAD thing. It will cause inline waits inside
- * of the USB interrupt handler. The correct way to handle this is to
- * enable the correct TxFIFO interrupt and wait until the Tx FIFO is empty.
- * Unfortunately, the interrupt driven logic is not working... Please fix!
- */
-
-#define ENABLE_DTXFSTS_POLLHACK 1
-
/* Debug ***********************************************************************/
/* Trace error codes */
@@ -184,8 +175,9 @@
#define STM32_TRACEERR_NOEP 0x18
#define STM32_TRACEERR_NOTCONFIGURED 0x19
#define STM32_TRACEERR_EPOUTQEMPTY 0x1a
-#define STM32_TRACEERR_EPINQEMPTY 0x1b
+#define STM32_TRACEERR_EPINREQEMPTY 0x1b
#define STM32_TRACEERR_NOOUTSETUP 0x1c
+#define STM32_TRACEERR_POLLTIMEOUT 0x1d
/* Trace interrupt codes */
@@ -432,7 +424,6 @@ struct stm32_usbdev_s
uint8_t stalled:1; /* 1: Protocol stalled */
uint8_t selfpowered:1; /* 1: Device is self powered */
- uint8_t connected:1; /* 1: Host connected */
uint8_t addressed:1; /* 1: Peripheral address has been set */
uint8_t configured:1; /* 1: Class driver has been configured */
uint8_t wakeup:1; /* 1: Device remote wake-up */
@@ -508,7 +499,7 @@ static void stm32_ep0out_ctrlsetup(FAR struct stm32_usbdev_s *priv);
static void stm32_txfifo_write(FAR struct stm32_ep_s *privep,
FAR uint8_t *buf, int nbytes);
static void stm32_epin_transfer(FAR struct stm32_ep_s *privep,
- FAR uint8_t *buf, int nbytes);
+ FAR uint8_t *buf, int nbytes);
static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
FAR struct stm32_ep_s *privep);
@@ -962,7 +953,7 @@ static void stm32_txfifo_write(FAR struct stm32_ep_s *privep,
regval |= ((uint32_t)*buf++) << 16;
regval |= ((uint32_t)*buf++) << 24;
- /* Then write the packed data to the TxFIFO */
+ /* Then write the packet data to the TxFIFO */
stm32_putreg(regval, regaddr);
}
@@ -1082,9 +1073,6 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
struct stm32_req_s *privreq;
uint32_t regaddr;
uint32_t regval;
-#ifdef ENABLE_DTXFSTS_POLLHACK
- int32_t timeout;
-#endif
uint8_t *buf;
int nbytes;
int nwords;
@@ -1113,7 +1101,7 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
privreq = stm32_rqpeek(privep);
if (!privreq)
{
- usbtrace(TRACE_DEVERROR(STM32_TRACEERR_EPINQEMPTY), privep->epphy);
+ usbtrace(TRACE_DEVERROR(STM32_TRACEERR_EPINREQEMPTY), privep->epphy);
/* There is no TX transfer in progress and no new pending TX
* requests to send. To stop transmitting any data on a particular
@@ -1151,13 +1139,20 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
privep->zlp = true;
}
- /* Loop while there are still bytes to be transferred (or a zero-length-
- * packet, ZLP, to be sent). The loop will also be terminated if there
- * is insufficient space remaining in the TxFIFO to send a complete
- * packet.
+ /* Add one more packet to the TxFIFO. We will wait for the transfer
+ * complete event before we add the next packet (or part of a packet
+ * to the TxFIFO).
+ *
+ * The documentation says that we can can multiple packets to the TxFIFO,
+ * but it seems that we need to get the transfer complete event before
+ * we can add the next (or maybe I have got something wrong?)
*/
+#if 0
while (privreq->req.xfrd < privreq->req.len || privep->zlp)
+#else
+ if (privreq->req.xfrd < privreq->req.len || privep->zlp)
+#endif
{
/* Get the number of bytes left to be sent in the request */
@@ -1219,25 +1214,9 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
regaddr = STM32_OTGFS_DTXFSTS(privep->epphy);
-#ifdef ENABLE_DTXFSTS_POLLHACK
- /* If ENABLE_DTXFSTS_POLLHACK is enabled , then poll DTXFSTS until
- * space in the TxFIFO is available. If it doesn't become available,
- * in a reasonable amount of time, then just pretend that it is.
- */
-
- for (timeout = 250000; timeout > 0; timeout--)
- {
- regval = stm32_getreg(regaddr);
- if ((regval & OTGFS_DTXFSTS_MASK) >= nwords)
- {
- break;
- }
- }
-#else
- /* If ENABLE_DTXFSTS_POLLHACK is not enabled, then check once for
- * space in the TxFIFO. If space in the TxFIFO is not available,
- * then set up an interrupt to resume the transfer when the TxFIFO
- * is empty.
+ /* Check for space in the TxFIFO. If space in the TxFIFO is not
+ * available, then set up an interrupt to resume the transfer when
+ * the TxFIFO is empty.
*/
regval = stm32_getreg(regaddr);
@@ -1253,11 +1232,12 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
empmsk |= OTGFS_DIEPEMPMSK(privep->epphy);
stm32_putreg(empmsk, STM32_OTGFS_DIEPEMPMSK);
- /* Terminate the transfer loop */
+ /* Terminate the transfer. We will try again when the TxFIFO empty
+ * interrupt is received.
+ */
- break;
+ return;
}
-#endif
/* Transfer data to the TxFIFO */
@@ -1290,11 +1270,12 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
if (privreq->req.xfrd >= privreq->req.len && !privep->zlp)
{
usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd);
- stm32_req_complete(privep, OK);
- /* The endpoint is no longer transferring data */
+ /* We are finished with the request (although the transfer has not
+ * yet completed).
+ */
- privep->active = false;
+ stm32_req_complete(privep, OK);
}
}
@@ -2690,7 +2671,7 @@ static inline void stm32_epin_txfifoempty(FAR struct stm32_usbdev_s *priv, int e
FAR struct stm32_ep_s *privep = &priv->epin[epno];
/* Continue processing the write request queue. This may mean sending
- * more dat from the exisiting request or terminating the current requests
+ * more data from the exisiting request or terminating the current requests
* and (perhaps) starting the IN transfer from the next write request.
*/
@@ -2741,9 +2722,11 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv)
mask = stm32_getreg(STM32_OTGFS_DIEPMSK);
- /* Check for FIFO not empty. Bits n corresponds to endpoint n.
- * That condition corresponds to bit 7 of the DIEPINT interrupt
- * status register.
+ /* Check if the TxFIFO not empty interrupt is enabled for this
+ * endpoint in the DIEPMSK register. Bits n corresponds to
+ * endpoint n in the register. That condition corresponds to
+ * bit 7 of the DIEPINT interrupt status register. There is
+ * no TXFE bit in the mask register, so we fake one here.
*/
empty = stm32_getreg(STM32_OTGFS_DIEPEMPMSK);
@@ -2763,11 +2746,13 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv)
if ((diepint & OTGFS_DIEPINT_XFRC) != 0)
{
- usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC), (uint16_t)diepint);
+ usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_XFRC),
+ (uint16_t)diepint);
- /* It is possible that logic may be waiting for a the TxFIFO to become
- * empty. We disable the TxFIFO empty interrupt here; it will be
- * re-enabled if there is still insufficient space in the TxFIFO.
+ /* It is possible that logic may be waiting for a the
+ * TxFIFO to become empty. We disable the TxFIFO empty
+ * interrupt here; it will be re-enabled if there is still
+ * insufficient space in the TxFIFO.
*/
empty &= ~OTGFS_DIEPEMPMSK(epno);
@@ -2828,7 +2813,7 @@ static inline void stm32_epin_interrupt(FAR struct stm32_usbdev_s *priv)
usbtrace(TRACE_INTDECODE(STM32_TRACEINTID_EPIN_TXFE), (uint16_t)diepint);
/* If we were waiting for TxFIFO to become empty, the we might have both
- * XFRC and TXFE interrups pending. Since we do the same thing for both
+ * XFRC and TXFE interrupts pending. Since we do the same thing for both
* cases, ignore the TXFE if we have already processed the XFRC.
*/
@@ -2886,6 +2871,13 @@ static inline void stm32_resumeinterrupt(FAR struct stm32_usbdev_s *priv)
/* Restore full power -- whatever that means for this particular board */
stm32_usbsuspend((struct usbdev_s *)priv, true);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
}
/*******************************************************************************
@@ -2900,7 +2892,16 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv)
{
#ifdef CONFIG_USBDEV_LOWPOWER
uint32_t regval;
+#endif
+
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+#ifdef CONFIG_USBDEV_LOWPOWER
/* OTGFS_DSTS_SUSPSTS is set as long as the suspend condition is detected
* on USB. Check if we are still have the suspend condition, that we are
* connected to the host, and that we have been configured.
@@ -2908,9 +2909,7 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv)
regval = stm32_getreg(STM32_OTGFS_DSTS);
- if ((regval & OTGFS_DSTS_SUSPSTS) != 0 &&
- priv->connected &&
- devstate == DEVSTATE_CONFIGURED)
+ if ((regval & OTGFS_DSTS_SUSPSTS) != 0 && devstate == DEVSTATE_CONFIGURED)
{
/* Switch off OTG FS clocking. Setting OTGFS_PCGCCTL_STPPCLK stops the
* PHY clock.
@@ -4957,8 +4956,9 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
/* At startup the core is in FS mode. */
- /* Disable the USB global interrupt by clearing GINTMSK in the global OTG
- * FS AHB configuration register.
+ /* Disable global interrupts by clearing the GINTMASK bit in the GAHBCFG
+ * register; Set the TXFELVL bit in the GAHBCFG register so that TxFIFO
+ * interrupts will occur when the TxFIFO is truly empty (not just half full).
*/
stm32_putreg(OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG);
@@ -5074,6 +5074,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
stm32_putreg(0, STM32_OTGFS_DIEPMSK);
stm32_putreg(0, STM32_OTGFS_DOEPMSK);
+ stm32_putreg(0, STM32_OTGFS_DIEPEMPMSK);
stm32_putreg(0xffffffff, STM32_OTGFS_DAINT);
stm32_putreg(0, STM32_OTGFS_DAINTMSK);
@@ -5155,10 +5156,13 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
stm32_putreg(regval, STM32_OTGFS_GINTMSK);
/* Enable the USB global interrupt by setting GINTMSK in the global OTG
- * FS AHB configuration register.
+ * FS AHB configuration register; Set the TXFELVL bit in the GAHBCFG
+ * register so that TxFIFO interrupts will occur when the TxFIFO is truly
+ * empty (not just half full).
*/
- stm32_putreg(OTGFS_GAHBCFG_GINTMSK | OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG);
+ stm32_putreg(OTGFS_GAHBCFG_GINTMSK | OTGFS_GAHBCFG_TXFELVL,
+ STM32_OTGFS_GAHBCFG);
}
/*******************************************************************************
@@ -5314,6 +5318,7 @@ void up_usbuninitialize(void)
stm32_putreg(0, STM32_OTGFS_DIEPMSK);
stm32_putreg(0, STM32_OTGFS_DOEPMSK);
+ stm32_putreg(0, STM32_OTGFS_DIEPEMPMSK);
stm32_putreg(0, STM32_OTGFS_DAINTMSK);
stm32_putreg(0xffffffff, STM32_OTGFS_DAINT);
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index 6aaecb2d9..c91f6a6d7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -2077,7 +2077,8 @@ void up_serialinit(void)
{
#ifdef HAVE_UART
char devname[16];
- unsigned i, j;
+ unsigned i;
+ unsigned minor = 0;
#ifdef CONFIG_PM
int ret;
#endif
@@ -2094,6 +2095,7 @@ void up_serialinit(void)
#if CONSOLE_UART > 0
(void)uart_register("/dev/console", &uart_devs[CONSOLE_UART - 1]->dev);
(void)uart_register("/dev/ttyS0", &uart_devs[CONSOLE_UART - 1]->dev);
+ minor = 1;
/* If we need to re-initialise the console to enable DMA do that here. */
@@ -2107,19 +2109,19 @@ void up_serialinit(void)
strcpy(devname, "/dev/ttySx");
- for (i = 0, j = 1; i < STM32_NUSART; i++)
+ for (i = 0; i < STM32_NUSART; i++)
{
- /* don't create a device for the console - we did that above */
+ /* Don't create a device for the console - we did that above */
if ((uart_devs[i] == 0) || (uart_devs[i]->dev.isconsole))
{
continue;
}
- /* register USARTs as devices in increasing order */
+ /* Register USARTs as devices in increasing order */
- devname[9] = '0' + j++;
+ devname[9] = '0' + minor++;
(void)uart_register(devname, &uart_devs[i]->dev);
}
#endif /* HAVE UART */
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index 8de698cd5..b4a4f36ab 100644
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -130,14 +130,28 @@
/* DMA channel configuration */
-#define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC )
-#define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC )
-#define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS )
-#define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS )
-#define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
-#define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR)
-#define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR)
-#define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR)
+#if defined(CONFIG_STM32_STM32F10XX)
+# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC )
+# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC )
+# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS )
+# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS )
+# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
+# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR)
+# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR)
+# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR)
+#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_P2M)
+# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_P2M)
+# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_P2M)
+# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_P2M)
+# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_M2P)
+# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_M2P)
+# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_M2P)
+# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_M2P)
+#else
+# error "Unknown STM32 DMA"
+#endif
+
/* Debug ****************************************************************************/
/* Check if (non-standard) SPI debug is enabled */
@@ -550,6 +564,21 @@ static inline void spi_dmarxwakeup(FAR struct stm32_spidev_s *priv)
#endif
/************************************************************************************
+ * Name: spi_dmatxwakeup
+ *
+ * Description:
+ * Signal that DMA is complete
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_SPI_DMA
+static inline void spi_dmatxwakeup(FAR struct stm32_spidev_s *priv)
+{
+ (void)sem_post(&priv->txsem);
+}
+#endif
+
+/************************************************************************************
* Name: spi_dmarxcallback
*
* Description:
@@ -1183,8 +1212,8 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
FAR void *rxbuffer, size_t nwords)
{
FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
- uint16_t rxdummy = 0xffff;
- uint16_t txdummy;
+ static uint16_t rxdummy = 0xffff;
+ static const uint16_t txdummy = 0xffff;
spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
DEBUGASSERT(priv && priv->spibase);
@@ -1330,6 +1359,8 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
priv->rxdma = stm32_dmachannel(priv->rxch);
priv->txdma = stm32_dmachannel(priv->txch);
DEBUGASSERT(priv->rxdma && priv->txdma);
+
+ spi_putreg(priv, STM32_SPI_CR2_OFFSET, SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN);
#endif
/* Enable spi */
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbdev.c b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
index 602de3824..d13ac8f96 100644
--- a/nuttx/arch/arm/src/stm32/stm32_usbdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
@@ -2346,6 +2346,13 @@ static void stm32_suspend(struct stm32_usbdev_s *priv)
{
uint16_t regval;
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
/* Disable ESOF polling, disable the SUSP interrupt, and enable the WKUP
* interrupt. Clear any pending WKUP interrupt.
*/
@@ -2411,6 +2418,13 @@ static void stm32_initresume(struct stm32_usbdev_s *priv)
/* Reset FSUSP bit and enable normal interrupt handling */
stm32_putreg(STM32_CNTR_SETUP, STM32_USB_CNTR);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
}
/****************************************************************************
diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig
index 8d6c0bb18..6e5f7c251 100644
--- a/nuttx/binfmt/Kconfig
+++ b/nuttx/binfmt/Kconfig
@@ -72,9 +72,10 @@ config PIC
config BINFMT_CONSTRUCTORS
bool "C++ Static Constructor Support"
default n
- depends on HAVE_CXX && ELF # FIX ME: Currently only supported for ELF
+ depends on HAVE_CXX && SCHED_STARTHOOK && ELF
---help---
- Build in support for C++ constructors in loaded modules.
+ Build in support for C++ constructors in loaded modules. Currently
+ only support for ELF binary formats.
config SYMTAB_ORDEREDBYNAME
bool "Symbol Tables Ordered by Name"
diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c
index afa445abb..10068b482 100644
--- a/nuttx/binfmt/binfmt_execmodule.c
+++ b/nuttx/binfmt/binfmt_execmodule.c
@@ -58,6 +58,14 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* If C++ constructors are used, then CONFIG_SCHED_STARTHOOK must also be
+ * selected be the start hook is used to schedule execution of the
+ * constructors.
+ */
+
+#if defined(CONFIG_BINFMT_CONSTRUCTORS) && !defined(CONFIG_SCHED_STARTHOOK)
+# errror "CONFIG_SCHED_STARTHOOK must be defined to use constructors"
+#endif
/****************************************************************************
* Private Function Prototypes
@@ -75,7 +83,9 @@
* Name: exec_ctors
*
* Description:
- * Execute C++ static constructors.
+ * Execute C++ static constructors. This function is registered as a
+ * start hook and runs on the thread of the newly created task before
+ * the new task's main function is called.
*
* Input Parameters:
* loadinfo - Load state information
@@ -87,26 +97,12 @@
****************************************************************************/
#ifdef CONFIG_BINFMT_CONSTRUCTORS
-static inline int exec_ctors(FAR const struct binary_s *binp)
+static void exec_ctors(FAR void *arg)
{
+ FAR const struct binary_s *binp = (FAR const struct binary_s *)arg;
binfmt_ctor_t *ctor = binp->ctors;
-#ifdef CONFIG_ADDRENV
- hw_addrenv_t oldenv;
- int ret;
-#endif
int i;
- /* Instantiate the address enviroment containing the constructors */
-
-#ifdef CONFIG_ADDRENV
- ret = up_addrenv_select(binp->addrenv, &oldenv);
- if (ret < 0)
- {
- bdbg("up_addrenv_select() failed: %d\n", ret);
- return ret;
- }
-#endif
-
/* Execute each constructor */
for (i = 0; i < binp->nctors; i++)
@@ -116,14 +112,6 @@ static inline int exec_ctors(FAR const struct binary_s *binp)
(*ctor)();
ctor++;
}
-
- /* Restore the address enviroment */
-
-#ifdef CONFIG_ADDRENV
- return up_addrenv_restore(oldenv);
-#else
- return OK;
-#endif
}
#endif
@@ -139,7 +127,7 @@ static inline int exec_ctors(FAR const struct binary_s *binp)
*
* Returned Value:
* This is an end-user function, so it follows the normal convention:
- * Returns the PID of the exec'ed module. On failure, it.returns
+ * Returns the PID of the exec'ed module. On failure, it returns
* -1 (ERROR) and sets errno appropriately.
*
****************************************************************************/
@@ -229,22 +217,19 @@ int exec_module(FAR const struct binary_s *binp)
}
#endif
- /* Get the assigned pid before we start the task */
-
- pid = tcb->pid;
-
- /* Execute all of the C++ static constructors */
+ /* Setup a start hook that will execute all of the C++ static constructors
+ * on the newly created thread. The struct binary_s must persist at least
+ * until the new task has been started.
+ */
#ifdef CONFIG_BINFMT_CONSTRUCTORS
- ret = exec_ctors(binp);
- if (ret < 0)
- {
- err = -ret;
- bdbg("exec_ctors() failed: %d\n", ret);
- goto errout_with_stack;
- }
+ task_starthook(tcb, exec_ctors, (FAR void *)binp);
#endif
+ /* Get the assigned pid before we start the task */
+
+ pid = tcb->pid;
+
/* Then activate the task at the provided priority */
ret = task_activate(tcb);
diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h
index 4fab9724d..fa750543a 100644
--- a/nuttx/binfmt/binfmt_internal.h
+++ b/nuttx/binfmt/binfmt_internal.h
@@ -71,7 +71,7 @@ EXTERN FAR struct binfmt_s *g_binfmts;
* Public Function Prototypes
***********************************************************************/
-/* Dump the contents of strtuc binary_s */
+/* Dump the contents of struct binary_s */
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT)
EXTERN int dump_module(FAR const struct binary_s *bin);
diff --git a/nuttx/binfmt/libelf/libelf_read.c b/nuttx/binfmt/libelf/libelf_read.c
index f4b725183..25ee7ba29 100644
--- a/nuttx/binfmt/libelf/libelf_read.c
+++ b/nuttx/binfmt/libelf/libelf_read.c
@@ -54,7 +54,7 @@
****************************************************************************/
#undef ELF_DUMP_READDATA /* Define to dump all file data read */
-#define DUMPER lib_rawprintf /* If ELF_DUMP_READDATA is defined, this
+#define DUMPER syslog /* If ELF_DUMP_READDATA is defined, this
* is the API used to dump data */
/****************************************************************************
diff --git a/nuttx/binfmt/libnxflat/libnxflat_read.c b/nuttx/binfmt/libnxflat/libnxflat_read.c
index 8deeb0805..103a81f81 100644
--- a/nuttx/binfmt/libnxflat/libnxflat_read.c
+++ b/nuttx/binfmt/libnxflat/libnxflat_read.c
@@ -55,7 +55,7 @@
****************************************************************************/
#undef NXFLAT_DUMP_READDATA /* Define to dump all file data read */
-#define DUMPER lib_rawprintf /* If NXFLAT_DUMP_READDATA is defined, this
+#define DUMPER syslog /* If NXFLAT_DUMP_READDATA is defined, this
* is the API used to dump data */
/****************************************************************************
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 1b78567a3..8d9bb381f 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -261,7 +261,7 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_DEBUG - enables built-in debug options
CONFIG_DEBUG_VERBOSE - enables verbose debug output
- CCONFIG_DEBUG_ENABLE - Support an interface to enable or disable debug output.
+ CCONFIG_SYSLOG_ENABLE - Support an interface to enable or disable debug output.
CONFIG_DEBUG_SYMBOLS - build without optimization and with
debug symbols (needed for use with a debugger).
CONFIG_DEBUG_SCHED - enable OS debug output (disabled by
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 653f97de1..710e2fb5f 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -80,7 +80,6 @@ CONFIGURED_APPS += uORB
CONFIGURED_APPS += mavlink
CONFIGURED_APPS += mavlink_onboard
-CONFIGURED_APPS += gps
CONFIGURED_APPS += commander
CONFIGURED_APPS += sdlog
CONFIGURED_APPS += sensors
@@ -114,6 +113,7 @@ CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/stm32/adc
CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/hil
+CONFIGURED_APPS += drivers/gps
# Testing stuff
CONFIGURED_APPS += px4/sensors_bringup
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index fd783dec5..5a54e350c 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -246,6 +246,7 @@ CONFIG_AT24XX_MTD_BLOCKSIZE=256
#
CONFIG_SERIAL_TERMIOS=y
CONFIG_SERIAL_CONSOLE_REINIT=y
+CONFIG_STANDARD_SERIAL=y
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index 30ec5be08..1185813db 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -159,6 +159,7 @@ CONFIG_STM32_ADC3=n
# CONFIG_USARTn_2STOP - Two stop bits
#
CONFIG_SERIAL_TERMIOS=y
+CONFIG_STANDARD_SERIAL=y
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index 3ced01b58..f3d2c871a 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -3,6 +3,14 @@
# see misc/tools/kconfig-language.txt.
#
+config DISABLE_POLL
+ bool "Disable driver poll interfaces"
+ default n
+ ---help---
+ The sizes of drivers can be reduced if the poll() method is not
+ supported. If you do not use poll() or select(), then you can
+ select DISABLE_POLL to reduce the code footprint by a small amount.
+
config DEV_NULL
bool "Enable /dev/null"
default y
diff --git a/nuttx/drivers/lcd/mio283qt2.c b/nuttx/drivers/lcd/mio283qt2.c
index 1758e230c..4c8835eef 100644
--- a/nuttx/drivers/lcd/mio283qt2.c
+++ b/nuttx/drivers/lcd/mio283qt2.c
@@ -495,14 +495,14 @@ static void mio283qt2_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npi
{
int i, j;
- lib_rawprintf("\n%s:\n", msg);
+ syslog("\n%s:\n", msg);
for (i = 0; i < npixels; i += 16)
{
up_putc(' ');
- lib_rawprintf(" ");
+ syslog(" ");
for (j = 0; j < 16; j++)
{
- lib_rawprintf(" %04x", *run++);
+ syslog(" %04x", *run++);
}
up_putc('\n');
}
diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c
index e42b5bded..d78688be5 100644
--- a/nuttx/drivers/lcd/ssd1289.c
+++ b/nuttx/drivers/lcd/ssd1289.c
@@ -497,14 +497,14 @@ static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixe
{
int i, j;
- lib_rawprintf("\n%s:\n", msg);
+ syslog("\n%s:\n", msg);
for (i = 0; i < npixels; i += 16)
{
up_putc(' ');
- lib_rawprintf(" ");
+ syslog(" ");
for (j = 0; j < 16; j++)
{
- lib_rawprintf(" %04x", *run++);
+ syslog(" %04x", *run++);
}
up_putc('\n');
}
diff --git a/nuttx/drivers/loop.c b/nuttx/drivers/loop.c
index b5b5d82d8..4744ae0dd 100644
--- a/nuttx/drivers/loop.c
+++ b/nuttx/drivers/loop.c
@@ -268,7 +268,7 @@ static ssize_t loop_write(FAR struct inode *inode, const unsigned char *buffer,
size_t start_sector, unsigned int nsectors)
{
FAR struct loop_struct_s *dev;
- size_t nbyteswritten;
+ ssize_t nbyteswritten;
off_t offset;
int ret;
diff --git a/nuttx/drivers/mmcsd/mmcsd_debug.c b/nuttx/drivers/mmcsd/mmcsd_debug.c
index 0bd7f896e..8cb5b2a2a 100644
--- a/nuttx/drivers/mmcsd/mmcsd_debug.c
+++ b/nuttx/drivers/mmcsd/mmcsd_debug.c
@@ -56,9 +56,9 @@
/* This needs to match the logic in include/debug.h */
#ifdef CONFIG_CPP_HAVE_VARARGS
-# define message(format, arg...) lib_rawprintf(format, ##arg)
+# define message(format, arg...) syslog(format, ##arg)
#else
-# define message lib_rawprintf
+# define message syslog
#endif
/****************************************************************************
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index d437b7fea..3d4cf1dd1 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/mmcsd/mmcsd_spi.c
*
- * Copyright (C) 2008-2010, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2010, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -409,10 +409,14 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot,
int ret;
int i;
- /* Wait until the card is not busy */
+ /* Wait until the card is not busy. Some SD cards will not enter the IDLE
+ * state until CMD0 is sent for the first time, switching the card to SPI
+ * mode. Having a pull-up resistor on MISO may avoid this problem, but
+ * this check makes it work also without the pull-up.
+ */
ret = mmcsd_waitready(slot);
- if (ret != OK)
+ if (ret != OK && cmd != &g_cmd0)
{
return ret;
}
diff --git a/nuttx/drivers/mtd/at25.c b/nuttx/drivers/mtd/at25.c
index e35b794a5..c58b16122 100644
--- a/nuttx/drivers/mtd/at25.c
+++ b/nuttx/drivers/mtd/at25.c
@@ -691,14 +691,16 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev)
kfree(priv);
priv = NULL;
}
-
- /* Unprotect all sectors */
+ else
+ {
+ /* Unprotect all sectors */
- at25_writeenable(priv);
- SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
- (void)SPI_SEND(priv->dev, AT25_WRSR);
- (void)SPI_SEND(priv->dev, AT25_SR_UNPROT);
- SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
+ at25_writeenable(priv);
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
+ (void)SPI_SEND(priv->dev, AT25_WRSR);
+ (void)SPI_SEND(priv->dev, AT25_SR_UNPROT);
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
+ }
}
/* Return the implementation-specific state structure as the MTD device */
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index 2346ee2d6..203259aeb 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -179,10 +179,10 @@
/* Debug ********************************************************************/
#ifdef CONFIG_ENC28J60_REGDEBUG
-# define enc_wrdump(a,v) lib_lowprintf("ENC28J60: %02x<-%02x\n", a, v);
-# define enc_rddump(a,v) lib_lowprintf("ENC28J60: %02x->%02x\n", a, v);
-# define enc_cmddump(c) lib_lowprintf("ENC28J60: CMD: %02x\n", c);
-# define enc_bmdump(c,b,s) lib_lowprintf("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s);
+# define enc_wrdump(a,v) lowsyslog("ENC28J60: %02x<-%02x\n", a, v);
+# define enc_rddump(a,v) lowsyslog("ENC28J60: %02x->%02x\n", a, v);
+# define enc_cmddump(c) lowsyslog("ENC28J60: CMD: %02x\n", c);
+# define enc_bmdump(c,b,s) lowsyslog("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s);
#else
# define enc_wrdump(a,v)
# define enc_rddump(a,v)
@@ -773,56 +773,56 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
#if 0 /* Sometimes useful */
static void enc_rxdump(FAR struct enc_driver_s *priv)
{
- lib_lowprintf("Rx Registers:\n");
- lib_lowprintf(" EIE: %02x EIR: %02x\n",
- enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR));
- lib_lowprintf(" ESTAT: %02x ECON1: %02x ECON2: %02x\n",
- enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1),
- enc_rdgreg(priv, ENC_ECON2));
- lib_lowprintf(" ERXST: %02x %02x\n",
- enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL));
- lib_lowprintf(" ERXND: %02x %02x\n",
- enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL));
- lib_lowprintf(" ERXRDPT: %02x %02x\n",
- enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL));
- lib_lowprintf(" ERXFCON: %02x EPKTCNT: %02x\n",
- enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT));
- lib_lowprintf(" MACON1: %02x MACON3: %02x\n",
- enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3));
- lib_lowprintf(" MAMXFL: %02x %02x\n",
- enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
- lib_lowprintf(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n",
- enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2),
- enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4),
- enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6));
+ lowsyslog("Rx Registers:\n");
+ lowsyslog(" EIE: %02x EIR: %02x\n",
+ enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR));
+ lowsyslog(" ESTAT: %02x ECON1: %02x ECON2: %02x\n",
+ enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1),
+ enc_rdgreg(priv, ENC_ECON2));
+ lowsyslog(" ERXST: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL));
+ lowsyslog(" ERXND: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL));
+ lowsyslog(" ERXRDPT: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL));
+ lowsyslog(" ERXFCON: %02x EPKTCNT: %02x\n",
+ enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT));
+ lowsyslog(" MACON1: %02x MACON3: %02x\n",
+ enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3));
+ lowsyslog(" MAMXFL: %02x %02x\n",
+ enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
+ lowsyslog(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2),
+ enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4),
+ enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6));
}
#endif
#if 0 /* Sometimes useful */
static void enc_txdump(FAR struct enc_driver_s *priv)
{
- lib_lowprintf("Tx Registers:\n");
- lib_lowprintf(" EIE: %02x EIR: %02x ESTAT: %02x\n",
- enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),);
- lib_lowprintf(" ESTAT: %02x ECON1: %02x\n",
- enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1));
- lib_lowprintf(" ETXST: %02x %02x\n",
- enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL));
- lib_lowprintf(" ETXND: %02x %02x\n",
- enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL));
- lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
- enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
- enc_rdbreg(priv, ENC_MACON4));
- lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
- enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
- enc_rdbreg(priv, ENC_MACON4));
- lib_lowprintf(" MABBIPG: %02x MAIPG %02x %02x\n",
- enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH),
- enc_rdbreg(priv, ENC_MAIPGL));
- lib_lowprintf(" MACLCON1: %02x MACLCON2: %02x\n",
- enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2));
- lib_lowprintf(" MAMXFL: %02x %02x\n",
- enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
+ lowsyslog("Tx Registers:\n");
+ lowsyslog(" EIE: %02x EIR: %02x ESTAT: %02x\n",
+ enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),);
+ lowsyslog(" ESTAT: %02x ECON1: %02x\n",
+ enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1));
+ lowsyslog(" ETXST: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL));
+ lowsyslog(" ETXND: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL));
+ lowsyslog(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
+ enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
+ enc_rdbreg(priv, ENC_MACON4));
+ lowsyslog(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
+ enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
+ enc_rdbreg(priv, ENC_MACON4));
+ lowsyslog(" MABBIPG: %02x MAIPG %02x %02x\n",
+ enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH),
+ enc_rdbreg(priv, ENC_MAIPGL));
+ lowsyslog(" MACLCON1: %02x MACLCON2: %02x\n",
+ enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2));
+ lowsyslog(" MAMXFL: %02x %02x\n",
+ enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
}
#endif
diff --git a/nuttx/drivers/serial/Kconfig b/nuttx/drivers/serial/Kconfig
index a1e0dff49..119923a69 100644
--- a/nuttx/drivers/serial/Kconfig
+++ b/nuttx/drivers/serial/Kconfig
@@ -10,6 +10,9 @@ config DEV_LOWCONSOLE
---help---
Use the simple, low-level, write-only serial console driver (minimal support)
+config SERIAL_REMOVABLE
+ bool
+
config 16550_UART
bool "16550 UART Chip support"
default n
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index 8987f01b8..0fed1d6c5 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -1,7 +1,7 @@
/************************************************************************************
* drivers/serial/serial.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -158,7 +158,11 @@ static void uart_pollnotify(FAR uart_dev_t *dev, pollevent_t eventset)
struct pollfd *fds = dev->fds[i];
if (fds)
{
+#ifdef CONFIG_SERIAL_REMOVABLE
+ fds->revents |= ((fds->events | (POLLERR|POLLHUP)) & eventset);
+#else
fds->revents |= (fds->events & eventset);
+#endif
if (fds->revents != 0)
{
fvdbg("Report events: %02x\n", fds->revents);
@@ -208,18 +212,40 @@ static int uart_putxmitchar(FAR uart_dev_t *dev, int ch)
*/
flags = irqsave();
- dev->xmitwaiting = true;
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if the removable device is no longer connected while we
+ * have interrupts off. We do not want the transition to occur
+ * as a race condition before we begin the wait.
+ */
+
+ if (dev->disconnected)
+ {
+ irqrestore(flags);
+ return -ENOTCONN;
+ }
+#endif
/* Wait for some characters to be sent from the buffer with the TX
* interrupt enabled. When the TX interrupt is enabled, uart_xmitchars
* should execute and remove some of the data from the TX buffer.
*/
+ dev->xmitwaiting = true;
uart_enabletxint(dev);
ret = uart_takesem(&dev->xmitsem, true);
uart_disabletxint(dev);
irqrestore(flags);
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if the removable device was disconnected while we were
+ * waiting.
+ */
+
+ if (dev->disconnected)
+ {
+ return -ENOTCONN;
+ }
+#endif
/* Check if we were awakened by signal. */
if (ret < 0)
@@ -288,6 +314,17 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
if (up_interrupt_context() || getpid() == 0)
{
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to write to
+ * the device.
+ */
+
+ if (dev->disconnected)
+ {
+ return -ENOTCONN;
+ }
+#endif
+
/* up_putc() will be used to generate the output in a busy-wait loop.
* up_putc() is only available for the console device.
*/
@@ -317,6 +354,20 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
return ret;
}
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to write to the
+ * device. This check occurs after taking the xmit.sem because the
+ * disconnection event might have occurred while we were waiting for
+ * access to the transmit buffers.
+ */
+
+ if (dev->disconnected)
+ {
+ uart_givesem(&dev->xmit.sem);
+ return -ENOTCONN;
+ }
+#endif
+
/* Loop while we still have data to copy to the transmit buffer.
* we add data to the head of the buffer; uart_xmitchars takes the
* data from the end of the buffer.
@@ -392,9 +443,13 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
uart_givesem(&dev->xmit.sem);
- /* Were we interrupted by a signal? That should be the only condition that
- * uart_putxmitchar() should return an error.
- */
+ /* uart_putxmitchar() might return an error under one of two
+ * conditions: (1) The wait for buffer space might have been
+ * interrupted by a signal (ret should be -EINTR), or (2) if
+ * CONFIG_SERIAL_REMOVABLE is defined, then uart_putxmitchar()
+ * might also return if the serial device was disconnected
+ * (wtih -ENOTCONN).
+ */
if (ret < 0)
{
@@ -413,11 +468,11 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
}
else
{
- /* No data was transferred. Return -EINTR. The VFS layer will
- * set the errno value appropriately).
+ /* No data was transferred. Return the negated error. The VFS layer
+ * will set the errno value appropriately).
*/
- nread = -EINTR;
+ nread = -ret;
}
}
@@ -458,6 +513,22 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
while (recvd < buflen)
{
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to read any
+ * further from the device.
+ */
+
+ if (dev->disconnected)
+ {
+ if (recvd == 0)
+ {
+ recvd = -ENOTCONN;
+ }
+
+ break;
+ }
+#endif
+
/* Check if there is more data to return in the circular buffer.
* NOTE: Rx interrupt handling logic may aynchronously increment
* the head index but must not modify the tail index. The tail
@@ -548,6 +619,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
{
recvd = -EAGAIN;
}
+
break;
}
#else
@@ -599,20 +671,41 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
*/
flags = irqsave();
- dev->recvwaiting = true;
- uart_enablerxint(dev);
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if the removable device is no longer connected while
+ * we have interrupts off. We do not want the transition to
+ * occur as a race condition before we begin the wait.
+ */
+
+ if (dev->disconnected)
+ {
+ uart_enablerxint(dev);
+ irqrestore(flags);
+ ret = -ENOTCONN;
+ break;
+ }
+#endif
/* Now wait with the Rx interrupt re-enabled. NuttX will
* automatically re-enable global interrupts when this thread
* goes to sleep.
*/
+ dev->recvwaiting = true;
+ uart_enablerxint(dev);
ret = uart_takesem(&dev->recvsem, true);
irqrestore(flags);
- /* Was a signal received while waiting for data to be received? */
+ /* Was a signal received while waiting for data to be
+ * received? Was a removable device disconnected while
+ * we were waiting?
+ */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ if (ret < 0 || dev->disconnected)
+#else
if (ret < 0)
+#endif
{
/* POSIX requires that we return after a signal is received.
* If some bytes were read, we need to return the number of bytes
@@ -626,7 +719,11 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
* set the errno value appropriately.
*/
+#ifdef CONFIG_SERIAL_REMOVABLE
+ recvd = dev->disconnected ? -ENOTCONN : -EINTR;
+#else
recvd = -EINTR;
+#endif
}
break;
@@ -852,12 +949,12 @@ int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
if (ndx != dev->xmit.tail)
{
- eventset |= POLLOUT;
+ eventset |= (fds->events & POLLOUT);
}
uart_givesem(&dev->xmit.sem);
- /* Check if the receive buffer is empty
+ /* Check if the receive buffer is empty.
*
* Get exclusive access to the recv buffer indices. NOTE: that we do not
* let this wait be interrupted by a signal (we probably should, but that
@@ -867,11 +964,20 @@ int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
(void)uart_takesem(&dev->recv.sem, false);
if (dev->recv.head != dev->recv.tail)
{
- eventset |= POLLIN;
+ eventset |= (fds->events & POLLIN);
}
uart_givesem(&dev->recv.sem);
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if a removable device has been disconnected. */
+
+ if (dev->disconnected)
+ {
+ eventset |= (POLLERR|POLLHUP);
+ }
+#endif
+
if (eventset)
{
uart_pollnotify(dev, eventset);
@@ -971,6 +1077,7 @@ static int uart_close(FAR struct file *filep)
{
uart_shutdown(dev); /* Disable the UART */
}
+
irqrestore(flags);
uart_givesem(&dev->closesem);
@@ -1004,6 +1111,19 @@ static int uart_open(FAR struct file *filep)
return ret;
}
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to open the
+ * device. We check this after obtaining the close semaphore because
+ * we might have been waiting when the device was disconnected.
+ */
+
+ if (dev->disconnected)
+ {
+ ret = -ENOTCONN;
+ goto errout_with_sem;
+ }
+#endif
+
/* Start up serial port */
/* Increment the count of references to the device. */
@@ -1145,10 +1265,12 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
void uart_datareceived(FAR uart_dev_t *dev)
{
- /* Awaken any awaiting read() operations */
+ /* Is there a thread waiting for read data? */
if (dev->recvwaiting)
{
+ /* Yes... wake it up */
+
dev->recvwaiting = false;
(void)sem_post(&dev->recvsem);
}
@@ -1172,8 +1294,12 @@ void uart_datareceived(FAR uart_dev_t *dev)
void uart_datasent(FAR uart_dev_t *dev)
{
+ /* Is there a thread waiting for space in xmit.buffer? */
+
if (dev->xmitwaiting)
{
+ /* Yes... wake it up */
+
dev->xmitwaiting = false;
(void)sem_post(&dev->xmitsem);
}
@@ -1183,4 +1309,69 @@ void uart_datasent(FAR uart_dev_t *dev)
uart_pollnotify(dev, POLLOUT);
}
+/************************************************************************************
+ * Name: uart_connected
+ *
+ * Description:
+ * Serial devices (like USB serial) can be removed. In that case, the "upper
+ * half" serial driver must be informed that there is no longer a valid serial
+ * channel associated with the driver.
+ *
+ * In this case, the driver will terminate all pending transfers wint ENOTCONN and
+ * will refuse all further transactions while the "lower half" is disconnected.
+ * The driver will continue to be registered, but will be in an unusable state.
+ *
+ * Conversely, the "upper half" serial driver needs to know when the serial
+ * device is reconnected so that it can resume normal operations.
+ *
+ * Assumptions/Limitations:
+ * This function may be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+void uart_connected(FAR uart_dev_t *dev, bool connected)
+{
+ irqstate_t flags;
+
+ /* Is the device disconnected? */
+
+ flags = irqsave();
+ dev->disconnected = !connected;
+ if (!connected)
+ {
+ /* Yes.. wake up all waiting threads. Each thread should detect the
+ * disconnection and return the ENOTCONN error.
+ */
+
+ /* Is there a thread waiting for space in xmit.buffer? */
+
+ if (dev->xmitwaiting)
+ {
+ /* Yes... wake it up */
+
+ dev->xmitwaiting = false;
+ (void)sem_post(&dev->xmitsem);
+ }
+
+ /* Is there a thread waiting for read data? */
+
+ if (dev->recvwaiting)
+ {
+ /* Yes... wake it up */
+
+ dev->recvwaiting = false;
+ (void)sem_post(&dev->recvsem);
+ }
+
+ /* Notify all poll/select waiters that and hangup occurred */
+
+ uart_pollnotify(dev, (POLLERR|POLLHUP));
+ }
+
+ irqrestore(flags);
+}
+#endif
+
+
diff --git a/nuttx/drivers/syslog/ramlog.c b/nuttx/drivers/syslog/ramlog.c
index b3a2ad0f5..08bbbfb59 100644
--- a/nuttx/drivers/syslog/ramlog.c
+++ b/nuttx/drivers/syslog/ramlog.c
@@ -726,10 +726,10 @@ int ramlog_sysloginit(void)
*
* Description:
* This is the low-level system logging interface. The debugging/syslogging
- * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is
- * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses
+ * interfaces are syslog() and lowsyslog(). The difference is that
+ * the syslog() internface writes to fd=1 (stdout) whereas lowsyslog() uses
* a lower level interface that works from interrupt handlers. This
- * function is a a low-level interface used to implement lib_lowprintf()
+ * function is a a low-level interface used to implement lowsyslog()
* when CONFIG_RAMLOG_SYSLOG=y and CONFIG_SYSLOG=y
*
****************************************************************************/
diff --git a/nuttx/drivers/usbdev/Kconfig b/nuttx/drivers/usbdev/Kconfig
index 70c7a04f0..0752bb791 100644
--- a/nuttx/drivers/usbdev/Kconfig
+++ b/nuttx/drivers/usbdev/Kconfig
@@ -148,12 +148,21 @@ config COMPOSITE_VERSIONNO
endif
menuconfig PL2303
- bool "Emulates the Prolific PL2303 serial/USB converter"
+ bool "Prolific PL2303 serial/USB converter emulation"
default n
+ select SERIAL_REMOVABLE
---help---
This logic emulates the Prolific PL2303 serial/USB converter
if PL2303
+
+config PL2303_CONSOLE
+ bool "PL2303 console device"
+ default n
+ ---help---
+ Register the USB device as /dev/console so that is will be used
+ as the console device.
+
config PL2303_EPINTIN
int "Logical endpoint numbers"
default 1
@@ -208,18 +217,27 @@ config PL2303_VENDORSTR
config PL2303_PRODUCTSTR
string "Product string"
- default "USBdev Serial"
+ default "PL2303 Emulation"
endif
menuconfig CDCACM
bool "USB Modem (CDC ACM) support"
default n
+ select SERIAL_REMOVABLE
---help---
Enables USB Modem (CDC ACM) support
if CDCACM
+
+config CDCACM_CONSOLE
+ bool "CDC/ACM console device"
+ default n
+ ---help---
+ Register the USB device as /dev/console so that is will be used
+ as the console device.
+
config CDCACM_COMPOSITE
- bool "CDCACM composite support"
+ bool "CDC/ACM composite support"
default n
depends on USBDEV_COMPOSITE
---help---
@@ -256,10 +274,10 @@ config CDCACM_EP0MAXPACKET
config CDCACM_EPINTIN
int "Hardware endpoint that supports interrupt IN operation"
- default 2
+ default 1
---help---
The logical 7-bit address of a hardware endpoint that supports
- interrupt IN operation. Default 2.
+ interrupt IN operation. Default 1.
config CDCACM_EPINTIN_FSSIZE
int "Endpoint in full speed size"
@@ -277,10 +295,10 @@ config CDCACM_EPINTIN_HSSIZE
config CDCACM_EPBULKOUT
int "Endpoint bulk out"
- default 0
+ default 3
---help---
The logical 7-bit address of a hardware endpoint that supports
- bulk OUT operation
+ bulk OUT operation. Default: 3
config CDCACM_EPBULKOUT_FSSIZE
int "Endpoint bulk out full speed size"
@@ -298,10 +316,10 @@ config CDCACM_EPBULKOUT_HSSIZE
config CDCACM_EPBULKIN
int "Endpoint bulk in"
- default 0
+ default 2
---help---
The logical 7-bit address of a hardware endpoint that supports
- bulk IN operation
+ bulk IN operation. Default: 2
config CDCACM_EPBULKIN_FSSIZE
int "Endpoint bulk in full speed size"
@@ -336,7 +354,7 @@ config CDCACM_RXBUFSIZE
Size of the serial receive/transmit buffers
config CDCACM_TXBUFSIZE
- bool "Transmit buffer size"
+ int "Transmit buffer size"
default 256
---help---
Size of the serial receive/transmit buffers
@@ -364,7 +382,7 @@ config CDCACM_VENDORSTR
config CDCACM_PRODUCTSTR
string "Product string"
- default "USBdev Serial"
+ default "CDC/ACM Serial"
endif
menuconfig USBMSC
@@ -479,8 +497,8 @@ config USBMSC_PRODUCTID
default 0x00
config USBMSC_PRODUCTSTR
- string "Mass stroage product string"
- default "Mass stroage"
+ string "Mass storage product string"
+ default "Mass Storage"
config USBMSC_VERSIONNO
hex "USB MSC Version Number"
diff --git a/nuttx/drivers/usbdev/cdcacm.c b/nuttx/drivers/usbdev/cdcacm.c
index 97c9d7c77..cb8679976 100644
--- a/nuttx/drivers/usbdev/cdcacm.c
+++ b/nuttx/drivers/usbdev/cdcacm.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbdev/cdcacm.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -188,6 +188,12 @@ static int cdcacm_setup(FAR struct usbdevclass_driver_s *driver,
size_t outlen);
static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver,
FAR struct usbdev_s *dev);
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void cdcacm_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+static void cdcacm_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+#endif
/* UART Operations **********************************************************/
@@ -211,8 +217,13 @@ static const struct usbdevclass_driverops_s g_driverops =
cdcacm_unbind, /* unbind */
cdcacm_setup, /* setup */
cdcacm_disconnect, /* disconnect */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ cdcacm_suspend, /* suspend */
+ cdcacm_resume, /* resume */
+#else
NULL, /* suspend */
NULL, /* resume */
+#endif
};
/* Serial port **************************************************************/
@@ -570,6 +581,14 @@ static void cdcacm_resetconfig(FAR struct cdcacm_dev_s *priv)
priv->config = CDCACM_CONFIGIDNONE;
+ /* Inform the "upper half" driver that there is no (functional) USB
+ * connection.
+ */
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+ uart_connected(&priv->serdev, false);
+#endif
+
/* Disable endpoints. This should force completion of all pending
* transfers.
*/
@@ -731,10 +750,20 @@ static int cdcacm_setconfig(FAR struct cdcacm_dev_s *priv, uint8_t config)
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-ret);
goto errout;
}
+
priv->nrdq++;
}
+ /* We are successfully configured */
+
priv->config = config;
+
+ /* Inform the "upper half" driver that we are "open for business" */
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+ uart_connected(&priv->serdev, true);
+#endif
+
return OK;
errout:
@@ -823,6 +852,7 @@ static void cdcacm_rdcomplete(FAR struct usbdev_ep_s *ep,
{
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-req->result);
}
+
irqrestore(flags);
}
@@ -932,6 +962,7 @@ static int cdcacm_bind(FAR struct usbdevclass_driver_s *driver,
ret = -ENOMEM;
goto errout;
}
+
priv->ctrlreq->callback = cdcacm_ep0incomplete;
/* Pre-allocate all endpoints... the endpoints will not be functional
@@ -1575,12 +1606,20 @@ static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver,
}
#endif
- /* Reset the configuration */
+ /* Inform the "upper half serial driver that we have lost the USB serial
+ * connection.
+ */
flags = irqsave();
+#ifdef CONFIG_SERIAL_REMOVABLE
+ uart_connected(&priv->serdev, false);
+#endif
+
+ /* Reset the configuration */
+
cdcacm_resetconfig(priv);
- /* Clear out all data in the circular buffer */
+ /* Clear out all outgoing data in the circular buffer */
priv->serdev.xmit.head = 0;
priv->serdev.xmit.tail = 0;
@@ -1596,6 +1635,79 @@ static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver,
}
/****************************************************************************
+ * Name: cdcacm_suspend
+ *
+ * Description:
+ * Handle the USB suspend event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void cdcacm_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSSUSPEND, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* And let the "upper half" driver now that we are suspended */
+
+ uart_connected(&priv->serdev, false);
+}
+#endif
+
+/****************************************************************************
+ * Name: cdcacm_resume
+ *
+ * Description:
+ * Handle the USB resume event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void cdcacm_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSRESUME, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* Are we still configured? */
+
+ if (priv->config != CDCACM_CONFIGIDNONE)
+ {
+ /* Yes.. let the "upper half" know that have resumed */
+
+ uart_connected(&priv->serdev, true);
+ }
+}
+#endif
+
+/****************************************************************************
* Serial Device Methods
****************************************************************************/
@@ -2045,12 +2157,17 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev)
/* Initialize the serial driver sub-structure */
- priv->serdev.recv.size = CONFIG_CDCACM_RXBUFSIZE;
- priv->serdev.recv.buffer = priv->rxbuffer;
- priv->serdev.xmit.size = CONFIG_CDCACM_TXBUFSIZE;
- priv->serdev.xmit.buffer = priv->txbuffer;
- priv->serdev.ops = &g_uartops;
- priv->serdev.priv = priv;
+ /* The initial state is disconnected */
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+ priv->serdev.disconnected = true;
+#endif
+ priv->serdev.recv.size = CONFIG_CDCACM_RXBUFSIZE;
+ priv->serdev.recv.buffer = priv->rxbuffer;
+ priv->serdev.xmit.size = CONFIG_CDCACM_TXBUFSIZE;
+ priv->serdev.xmit.buffer = priv->txbuffer;
+ priv->serdev.ops = &g_uartops;
+ priv->serdev.priv = priv;
/* Initialize the USB class driver structure */
@@ -2148,7 +2265,7 @@ int cdcacm_initialize(int minor, FAR void **handle)
*
* Description:
* Un-initialize the USB storage class driver. This function is used
- * internally by the USB composite driver to unitialized the CDC/ACM
+ * internally by the USB composite driver to unitialize the CDC/ACM
* driver. This same interface is available (with an untyped input
* parameter) when the CDC/ACM driver is used standalone.
*
diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c
index d10539fa7..7b07a9cba 100644
--- a/nuttx/drivers/usbdev/pl2303.c
+++ b/nuttx/drivers/usbdev/pl2303.c
@@ -343,6 +343,12 @@ static int usbclass_setup(FAR struct usbdevclass_driver_s *driver,
size_t outlen);
static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
FAR struct usbdev_s *dev);
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void usbclass_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+static void usbclass_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+#endif
/* Serial port *************************************************************/
@@ -366,8 +372,13 @@ static const struct usbdevclass_driverops_s g_driverops =
usbclass_unbind, /* unbind */
usbclass_setup, /* setup */
usbclass_disconnect, /* disconnect */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ usbclass_suspend, /* suspend */
+ usbclass_resume, /* resume */
+#else
NULL, /* suspend */
NULL, /* resume */
+#endif
};
/* Serial port *************************************************************/
@@ -983,6 +994,14 @@ static void usbclass_resetconfig(FAR struct pl2303_dev_s *priv)
priv->config = PL2303_CONFIGIDNONE;
+ /* Inform the "upper half" driver that there is no (functional) USB
+ * connection.
+ */
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+ uart_connected(&priv->serdev, false);
+#endif
+
/* Disable endpoints. This should force completion of all pending
* transfers.
*/
@@ -1112,10 +1131,20 @@ static int usbclass_setconfig(FAR struct pl2303_dev_s *priv, uint8_t config)
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-ret);
goto errout;
}
+
priv->nrdq++;
}
+ /* We are successfully configured */
+
priv->config = config;
+
+ /* Inform the "upper half" driver that we are "open for business" */
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+ uart_connected(&priv->serdev, true);
+#endif
+
return OK;
errout:
@@ -1844,12 +1873,20 @@ static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
}
#endif
- /* Reset the configuration */
+ /* Inform the "upper half serial driver that we have lost the USB serial
+ * connection.
+ */
flags = irqsave();
+#ifdef CONFIG_SERIAL_REMOVABLE
+ uart_connected(&priv->serdev, false);
+#endif
+
+ /* Reset the configuration */
+
usbclass_resetconfig(priv);
- /* Clear out all data in the circular buffer */
+ /* Clear out all outgoing data in the circular buffer */
priv->serdev.xmit.head = 0;
priv->serdev.xmit.tail = 0;
@@ -1863,6 +1900,79 @@ static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
}
/****************************************************************************
+ * Name: usbclass_suspend
+ *
+ * Description:
+ * Handle the USB suspend event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void usbclass_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSSUSPEND, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* And let the "upper half" driver now that we are suspended */
+
+ uart_connected(&priv->serdev, false);
+}
+#endif
+
+/****************************************************************************
+ * Name: usbclass_resume
+ *
+ * Description:
+ * Handle the USB resume event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void usbclass_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSRESUME, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* Are we still configured? */
+
+ if (priv->config != PL2303_CONFIGIDNONE)
+ {
+ /* Yes.. let the "upper half" know that have resumed */
+
+ uart_connected(&priv->serdev, true);
+ }
+}
+#endif
+
+/****************************************************************************
* Serial Device Methods
****************************************************************************/
@@ -2185,12 +2295,15 @@ int usbdev_serialinitialize(int minor)
/* Initialize the serial driver sub-structure */
- priv->serdev.recv.size = CONFIG_PL2303_RXBUFSIZE;
- priv->serdev.recv.buffer = priv->rxbuffer;
- priv->serdev.xmit.size = CONFIG_PL2303_TXBUFSIZE;
- priv->serdev.xmit.buffer = priv->txbuffer;
- priv->serdev.ops = &g_uartops;
- priv->serdev.priv = priv;
+#ifdef CONFIG_SERIAL_REMOVABLE
+ priv->serdev.disconnected = true;
+#endif
+ priv->serdev.recv.size = CONFIG_PL2303_RXBUFSIZE;
+ priv->serdev.recv.buffer = priv->rxbuffer;
+ priv->serdev.xmit.size = CONFIG_PL2303_TXBUFSIZE;
+ priv->serdev.xmit.buffer = priv->txbuffer;
+ priv->serdev.ops = &g_uartops;
+ priv->serdev.priv = priv;
/* Initialize the USB class driver structure */
diff --git a/nuttx/drivers/usbdev/usbdev_trace.c b/nuttx/drivers/usbdev/usbdev_trace.c
index c8cc09292..c332c1358 100644
--- a/nuttx/drivers/usbdev/usbdev_trace.c
+++ b/nuttx/drivers/usbdev/usbdev_trace.c
@@ -168,9 +168,9 @@ void usbtrace(uint16_t event, uint16_t value)
}
}
#else
- /* Just print the data using lib_lowprintf */
+ /* Just print the data using lowsyslog */
- usbtrace_trprintf((trprintf_t)lib_lowprintf, event, value);
+ usbtrace_trprintf((trprintf_t)lowsyslog, event, value);
#endif
}
irqrestore(flags);
diff --git a/nuttx/drivers/usbdev/usbmsc.h b/nuttx/drivers/usbdev/usbmsc.h
index 883a49951..da35ae923 100644
--- a/nuttx/drivers/usbdev/usbmsc.h
+++ b/nuttx/drivers/usbdev/usbmsc.h
@@ -199,9 +199,9 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# ifdef CONFIG_ARCH_LOWPUTC
-# define dbgprintf(format, arg...) lib_lowprintf(format, ##arg)
+# define dbgprintf(format, arg...) lowsyslog(format, ##arg)
# else
-# define dbgprintf(format, arg...) lib_rawprintf(format, ##arg)
+# define dbgprintf(format, arg...) syslog(format, ##arg)
# endif
# else
# define dbgprintf(x...)
@@ -209,9 +209,9 @@
#else
# ifdef CONFIG_DEBUG
# ifdef CONFIG_ARCH_LOWPUTC
-# define dbgprintf lib_lowprintf
+# define dbgprintf lowsyslog
# else
-# define dbgprintf lib_rawprintf
+# define dbgprintf syslog
# endif
# else
# define dbgprintf (void)
diff --git a/nuttx/fs/Kconfig b/nuttx/fs/Kconfig
index dfbfda3fa..6aac7a3f7 100644
--- a/nuttx/fs/Kconfig
+++ b/nuttx/fs/Kconfig
@@ -5,6 +5,10 @@
comment "File system configuration"
+config DISABLE_MOUNTPOINT
+ bool "Disable support for mount points"
+ default n
+
source fs/mmap/Kconfig
source fs/fat/Kconfig
source fs/nfs/Kconfig
@@ -14,29 +18,43 @@ source fs/binfs/Kconfig
comment "System Logging"
-config SYSLOG
- bool "System logging"
+config SYSLOG_ENABLE
+ bool "Enable SYSLOG Controls"
default n
---help---
- Enables generic system logging features.
+ Support an interface called syslog_enable to dynamically enable or
+ disable SYSLOG output. Default: SYSLOG output is always enabled.
-config SYSLOG_DEVPATH
- string "System log device"
- default "/dev/syslog"
- depends on SYSLOG
+config SYSLOG
+ bool "Advanced SYSLOG features"
+ default n
---help---
- The full path to the system logging device. For the RAMLOG SYSLOG device,
- this is normally "/dev/ramlog". For character SYSLOG devices, it should be
- some other existing character device (or file) supported by the configuration
- (such as "/dev/ttyS1")/
+ Enables generic system logging features. NOTE: This setting is not
+ required to enable system logging. If this feature is not enable
+ system logging will still be available and will log to the system
+ console (like printf()). This setting is required to enable
+ customization of the basic system loggin capability.
+
+if SYSLOG
config SYSLOG_CHAR
bool "System log character device support"
default y
- depends on SYSLOG
---help---
Enable the generic character device for the SYSLOG. The full path to the
SYSLOG device is provided by SYSLOG_DEVPATH. A valid character device (or
file) must exist at this path. It will by opened by syslog_initialize.
Do not enable more than one SYSLOG device.
+
+config SYSLOG_DEVPATH
+ string "System log device"
+ default "/dev/syslog"
+ depends on SYSLOG_CHAR
+ ---help---
+ The full path to the system logging device. For the RAMLOG SYSLOG device,
+ this is normally "/dev/ramlog". For character SYSLOG devices, it should be
+ some other existing character device (or file) supported by the configuration
+ (such as "/dev/ttyS1")/
+
+endif
diff --git a/nuttx/fs/fat/fs_configfat.c b/nuttx/fs/fat/fs_configfat.c
index 2075caa9f..04141ee2b 100644
--- a/nuttx/fs/fat/fs_configfat.c
+++ b/nuttx/fs/fat/fs_configfat.c
@@ -406,7 +406,7 @@ mkfatfs_clustersearchlimits(FAR struct fat_format_s *fmt, FAR struct fat_var_s *
}
/****************************************************************************
- * Name: mkfatfs_try12
+ * Name: mkfatfs_tryfat12
*
* Description:
* Try to define a FAT12 filesystem on the device using the candidate
@@ -462,7 +462,7 @@ mkfatfs_tryfat12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
* FAT12 (remembering that two FAT cluster slots are reserved).
*/
- if (config->fc_nclusters > maxnclusters - 2)
+ if (config->fc_nclusters + 2 > maxnclusters)
{
fvdbg("Too many clusters for FAT12\n");
return -ENFILE;
@@ -472,7 +472,7 @@ mkfatfs_tryfat12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
}
/****************************************************************************
- * Name: mkfatfs_try16
+ * Name: mkfatfs_tryfat16
*
* Description:
* Try to define a FAT16 filesystem on the device using the candidate
@@ -532,7 +532,7 @@ mkfatfs_tryfat16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
* be confused as a FAT12 at mount time.
*/
- if ((config->fc_nclusters > maxnclusters - 2) ||
+ if ((config->fc_nclusters + 2 > maxnclusters) ||
(config->fc_nclusters < FAT_MINCLUST16))
{
fvdbg("Too few or too many clusters for FAT16\n");
@@ -543,7 +543,7 @@ mkfatfs_tryfat16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
}
/****************************************************************************
- * Name: mkfatfs_try32
+ * Name: mkfatfs_tryfat32
*
* Description:
* Try to define a FAT32 filesystem on the device using the candidate
@@ -587,7 +587,7 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
* maxnclusters = nfatsects * sectorsize / 4 - 2
*/
- maxnclusters = (config->fc_nfatsects >> (var->fv_sectshift - 2));
+ maxnclusters = (config->fc_nfatsects << (var->fv_sectshift - 2));
if (maxnclusters > FAT_MAXCLUST32)
{
maxnclusters = FAT_MAXCLUST32;
@@ -599,7 +599,7 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
* FAT32 (remembering that two FAT cluster slots are reserved).
*/
- if ((config->fc_nclusters > maxnclusters - 3) ||
+ if ((config->fc_nclusters + 3 > maxnclusters) ||
(config->fc_nclusters < FAT_MINCLUST32 && fmt->ff_fattype != 32))
{
fvdbg("Too few or too many clusters for FAT32\n");
diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c
index c10c28a5c..df8962b51 100644
--- a/nuttx/fs/fat/fs_fat32.c
+++ b/nuttx/fs/fat/fs_fat32.c
@@ -381,6 +381,7 @@ static int fat_close(FAR struct file *filep)
{
struct inode *inode;
struct fat_file_s *ff;
+ struct fat_mountpt_s *fs;
int ret = OK;
/* Sanity checks */
@@ -391,6 +392,7 @@ static int fat_close(FAR struct file *filep)
ff = filep->f_priv;
inode = filep->f_inode;
+ fs = inode->i_private;
/* Do not check if the mount is healthy. We must support closing of
* the file even when there is healthy mount.
@@ -408,6 +410,7 @@ static int fat_close(FAR struct file *filep)
if (ff->ff_buffer)
{
+ (void)fs; /* Unused if fat_io_free == free(). */
fat_io_free(ff->ff_buffer, fs->fs_hwsectorsize);
}
diff --git a/nuttx/fs/fat/fs_fat32util.c b/nuttx/fs/fat/fs_fat32util.c
index 9aa1d3992..8edef7735 100644
--- a/nuttx/fs/fat/fs_fat32util.c
+++ b/nuttx/fs/fat/fs_fat32util.c
@@ -106,8 +106,8 @@ static int fat_checkfsinfo(struct fat_mountpt_s *fs)
FSI_GETSTRUCTSIG(fs->fs_buffer) == 0x61417272 &&
FSI_GETTRAILSIG(fs->fs_buffer) == BOOT_SIGNATURE32)
{
- fs->fs_fsinextfree = FSI_GETFREECOUNT(fs->fs_buffer);
- fs->fs_fsifreecount = FSI_GETNXTFREE(fs->fs_buffer);
+ fs->fs_fsifreecount = FSI_GETFREECOUNT(fs->fs_buffer);
+ fs->fs_fsinextfree = FSI_GETNXTFREE(fs->fs_buffer);
return OK;
}
}
diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c
index fd6aa88a8..d8a370482 100644
--- a/nuttx/fs/fs_fdopen.c
+++ b/nuttx/fs/fs_fdopen.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_fdopen.c
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,9 +68,11 @@ static inline int fs_checkfd(FAR _TCB *tcb, int fd, int oflags)
FAR struct filelist *flist;
FAR struct inode *inode;
- /* Get the file list from the TCB */
+ DEBUGASSERT(tcb && tcb->group);
- flist = tcb->filelist;
+ /* Get the file list from the task group */
+
+ flist = &tcb->group->tg_filelist;
/* Get the inode associated with the file descriptor. This should
* normally be the case if fd >= 0. But not in the case where the
@@ -142,6 +144,7 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb)
{
tcb = sched_self();
}
+ DEBUGASSERT(tcb && tcb->group);
/* Verify that this is a valid file/socket descriptor and that the
* requested access can be support.
@@ -189,9 +192,9 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb)
/* Get the stream list from the TCB */
- slist = tcb->streams;
+ slist = &tcb->group->tg_streamlist;
- /* Find an unallocated FILE structure in the stream list */
+ /* Find an unallocated FILE structure in the stream list */
ret = sem_wait(&slist->sl_sem);
if (ret != OK)
diff --git a/nuttx/fs/fs_files.c b/nuttx/fs/fs_files.c
index 06addb1ef..c68ec7e73 100644
--- a/nuttx/fs/fs_files.c
+++ b/nuttx/fs/fs_files.c
@@ -155,56 +155,19 @@ void files_initialize(void)
}
/****************************************************************************
- * Name: files_alloclist
+ * Name: files_initlist
*
- * Description: Allocate a list of files for a new task
+ * Description: Initializes the list of files for a new task
*
****************************************************************************/
-FAR struct filelist *files_alloclist(void)
+void files_initlist(FAR struct filelist *list)
{
- FAR struct filelist *list;
- list = (FAR struct filelist*)kzalloc(sizeof(struct filelist));
- if (list)
- {
- /* Start with a reference count of one */
-
- list->fl_crefs = 1;
-
- /* Initialize the list access mutex */
+ DEBUGASSERT(list);
- (void)sem_init(&list->fl_sem, 0, 1);
- }
+ /* Initialize the list access mutex */
- return list;
-}
-
-/****************************************************************************
- * Name: files_addreflist
- *
- * Description:
- * Increase the reference count on a file list
- *
- ****************************************************************************/
-
-int files_addreflist(FAR struct filelist *list)
-{
- if (list)
- {
- /* Increment the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register irqstate_t flags = irqsave();
- list->fl_crefs++;
- irqrestore(flags);
- }
-
- return OK;
+ (void)sem_init(&list->fl_sem, 0, 1);
}
/****************************************************************************
@@ -215,51 +178,25 @@ int files_addreflist(FAR struct filelist *list)
*
****************************************************************************/
-int files_releaselist(FAR struct filelist *list)
+void files_releaselist(FAR struct filelist *list)
{
- int crefs;
- if (list)
- {
- /* Decrement the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register irqstate_t flags = irqsave();
- crefs = --(list->fl_crefs);
- irqrestore(flags);
-
- /* If the count decrements to zero, then there is no reference
- * to the structure and it should be deallocated. Since there
- * are references, it would be an error if any task still held
- * a reference to the list's semaphore.
- */
-
- if (crefs <= 0)
- {
- int i;
+ int i;
- /* Close each file descriptor .. Normally, you would need
- * take the list semaphore, but it is safe to ignore the
- * semaphore in this context because there are no references
- */
+ DEBUGASSERT(list);
- for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
- {
- (void)_files_close(&list->fl_files[i]);
- }
-
- /* Destroy the semaphore and release the filelist */
+ /* Close each file descriptor .. Normally, you would need take the list
+ * semaphore, but it is safe to ignore the semaphore in this context because
+ * there should not be any references in this context.
+ */
- (void)sem_destroy(&list->fl_sem);
- sched_free(list);
- }
+ for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++)
+ {
+ (void)_files_close(&list->fl_files[i]);
}
- return OK;
+ /* Destroy the semaphore */
+
+ (void)sem_destroy(&list->fl_sem);
}
/****************************************************************************
diff --git a/nuttx/fs/fs_syslog.c b/nuttx/fs/fs_syslog.c
index 1d569082a..d9ad29e0f 100644
--- a/nuttx/fs/fs_syslog.c
+++ b/nuttx/fs/fs_syslog.c
@@ -42,6 +42,7 @@
#include <sys/types.h>
#include <stdint.h>
+#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <semaphore.h>
@@ -167,8 +168,10 @@ static inline int syslog_takesem(void)
static inline void syslog_givesem(void)
{
+#ifdef CONFIG_DEBUG
pid_t me = getpid();
DEBUGASSERT(g_sysdev.sl_holder == me);
+#endif
/* Relinquish the semaphore */
@@ -265,7 +268,7 @@ int syslog_initialize(void)
{
/* The inode was not found. In this case, we will attempt to re-open
* the device repeatedly. The assumption is that the device path is
- * value but that the driver has not yet been registered.
+ * valid but that the driver has not yet been registered.
*/
g_sysdev.sl_state = SYSLOG_REOPEN;
@@ -282,7 +285,7 @@ int syslog_initialize(void)
if (!INODE_IS_DRIVER(inode))
#endif
{
- ret = ENXIO;
+ ret = -ENXIO;
goto errout_with_inode;
}
@@ -290,7 +293,7 @@ int syslog_initialize(void)
if (!inode->u.i_ops || !inode->u.i_ops->write)
{
- return -EACCES;
+ ret = -EACCES;
goto errout_with_inode;
}
@@ -346,8 +349,8 @@ int syslog_initialize(void)
return OK;
errout_with_inode:
- g_sysdev.sl_state = SYSLOG_FAILURE;
inode_release(inode);
+ g_sysdev.sl_state = SYSLOG_FAILURE;
return ret;
}
@@ -356,16 +359,18 @@ int syslog_initialize(void)
*
* Description:
* This is the low-level system logging interface. The debugging/syslogging
- * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is
- * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses
+ * interfaces are syslog() and lowsyslog(). The difference is is that
+ * the syslog() function writes to fd=1 (stdout) whereas lowsyslog() uses
* a lower level interface that works from interrupt handlers. This
- * function is a a low-level interface used to implement lib_lowprintf().
+ * function is a a low-level interface used to implement lowsyslog().
*
****************************************************************************/
int syslog_putc(int ch)
{
ssize_t nbytes;
+ uint8_t uch;
+ int errcode;
int ret;
/* Ignore any output:
@@ -382,7 +387,10 @@ int syslog_putc(int ch)
* (4) Any debug output generated from interrupt handlers. A disadvantage
* of using the generic character device for the SYSLOG is that it
* cannot handle debug output generated from interrupt level handlers.
- * (5) If an irrecoverable failure occurred during initialization. In
+ * (5) Any debug output generated from the IDLE loop. The character
+ * driver interface is blocking and the IDLE thread is not permitted
+ * to block.
+ * (6) If an irrecoverable failure occurred during initialization. In
* this case, we won't ever bother to try again (ever).
*
* NOTE: That the third case is different. It applies only to the thread
@@ -390,11 +398,12 @@ int syslog_putc(int ch)
* that is why that case is handled in syslog_semtake().
*/
- /* Case (4) */
+ /* Cases (4) and (5) */
- if (up_interrupt_context())
+ if (up_interrupt_context() || getpid() == 0)
{
- return -ENOSYS; /* Not supported */
+ errcode = ENOSYS;
+ goto errout_with_errcode;
}
/* We can save checks in the usual case: That after the SYSLOG device
@@ -408,14 +417,16 @@ int syslog_putc(int ch)
if (g_sysdev.sl_state == SYSLOG_UNINITIALIZED ||
g_sysdev.sl_state == SYSLOG_INITIALIZING)
{
- return -EAGAIN; /* Can't access the SYSLOG now... maybe next time? */
+ errcode = EAGAIN; /* Can't access the SYSLOG now... maybe next time? */
+ goto errout_with_errcode;
}
- /* Case (5) */
+ /* Case (6) */
if (g_sysdev.sl_state == SYSLOG_FAILURE)
{
- return -ENXIO; /* There is no SYSLOG device */
+ errcode = ENXIO; /* There is no SYSLOG device */
+ goto errout_with_errcode;
}
/* syslog_initialize() is called as soon as enough of the operating
@@ -443,7 +454,8 @@ int syslog_putc(int ch)
if (ret < 0)
{
sched_unlock();
- return ret;
+ errcode = -ret;
+ goto errout_with_errcode;
}
}
@@ -471,7 +483,8 @@ int syslog_putc(int ch)
* way, we are outta here.
*/
- return ret;
+ errcode = -ret;
+ goto errout_with_errcode;
}
/* Pre-pend a newline with a carriage return. */
@@ -497,19 +510,27 @@ int syslog_putc(int ch)
{
/* Write the non-newline character (and don't flush) */
- nbytes = syslog_write(&ch, 1);
+ uch = (uint8_t)ch;
+ nbytes = syslog_write(&uch, 1);
}
syslog_givesem();
- /* Check if the write was successful */
+ /* Check if the write was successful. If not, nbytes will be
+ * a negated errno value.
+ */
if (nbytes < 0)
{
- return nbytes;
+ errcode = -ret;
+ goto errout_with_errcode;
}
return ch;
+
+errout_with_errcode:
+ set_errno(errcode);
+ return EOF;
}
#endif /* CONFIG_SYSLOG && CONFIG_SYSLOG_CHAR */
diff --git a/nuttx/fs/nxffs/nxffs_dump.c b/nuttx/fs/nxffs/nxffs_dump.c
index 6a89aaf1d..9caac4c4b 100644
--- a/nuttx/fs/nxffs/nxffs_dump.c
+++ b/nuttx/fs/nxffs/nxffs_dump.c
@@ -60,7 +60,7 @@
*/
#undef fdbg
-#define fdbg lib_rawprintf
+#define fdbg syslog
/****************************************************************************
* Private Types
diff --git a/nuttx/graphics/nxfonts/nxfonts_getfont.c b/nuttx/graphics/nxfonts/nxfonts_getfont.c
index c2af977f2..0eb48e9df 100644
--- a/nuttx/graphics/nxfonts/nxfonts_getfont.c
+++ b/nuttx/graphics/nxfonts/nxfonts_getfont.c
@@ -242,7 +242,7 @@ static FAR const struct nx_fontpackage_s *g_fontpackages[] =
* Name: nxf_getglyphset
*
* Description:
- * Return information about the font set containtined he selected
+ * Return information about the font set contained in the selected
* character encoding.
*
* Input Parameters:
diff --git a/nuttx/include/assert.h b/nuttx/include/assert.h
index 31c9edf48..62ffb3a6e 100644
--- a/nuttx/include/assert.h
+++ b/nuttx/include/assert.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/assert.h
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -100,23 +100,28 @@
****************************************************************************/
/****************************************************************************
- * Global Function Prototypes
+ * Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
#ifdef CONFIG_HAVE_FILENAME
-EXTERN void up_assert(FAR const uint8_t *filename, int linenum);
-EXTERN void up_assert_code(FAR const uint8_t *filename, int linenum,
- int errcode);
+void up_assert(FAR const uint8_t *filename, int linenum) noreturn_function;
+void up_assert_code(FAR const uint8_t *filename, int linenum, int errcode)
+ noreturn_function;
#else
-EXTERN void up_assert(void);
-EXTERN void up_assert_code(int errcode);
+void up_assert(void) noreturn_function;
+void up_assert_code(int errcode) noreturn_function;
#endif
#undef EXTERN
diff --git a/nuttx/include/debug.h b/nuttx/include/debug.h
index aa5efd432..70ae2ee18 100644
--- a/nuttx/include/debug.h
+++ b/nuttx/include/debug.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/debug.h
*
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
-#include <stdint.h>
+#include <syslog.h>
/****************************************************************************
* Pre-processor Definitions
@@ -104,22 +104,22 @@
#ifdef CONFIG_DEBUG
# define dbg(format, arg...) \
- lib_rawprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ syslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# ifdef CONFIG_ARCH_LOWPUTC
# define lldbg(format, arg...) \
- lib_lowprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ lowsyslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# else
# define lldbg(x...)
# endif
# ifdef CONFIG_DEBUG_VERBOSE
# define vdbg(format, arg...) \
- lib_rawprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ syslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# ifdef CONFIG_ARCH_LOWPUTC
# define llvdbg(format, arg...) \
- lib_lowprintf(EXTRA_FMT format EXTRA_ARG, ##arg)
+ lowsyslog(EXTRA_FMT format EXTRA_ARG, ##arg)
# else
# define llvdbg(x...)
# endif
@@ -576,29 +576,16 @@ extern "C"
{
#endif
-/* These low-level debug APIs are provided by the NuttX library. If the
- * cross-compiler's pre-processor supports a variable number of macro
- * arguments, then the macros below will map all debug statements to one
- * or the other of the following.
- */
-
-int lib_rawprintf(FAR const char *format, ...);
-
-#ifdef CONFIG_ARCH_LOWPUTC
-int lib_lowprintf(FAR const char *format, ...);
-#endif
-
/* Dump a buffer of data */
void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen);
-/* Enable or disable debug output */
-
-#ifdef CONFIG_DEBUG_ENABLE
-void dbg_enable(bool enable);
-#endif
-
-/* If the cross-compiler's pre-processor does not support variable length
+/* The system logging interfaces are pnormally accessed via the macros
+ * provided above. If the cross-compiler's C pre-processor supports a
+ * variable number of macro arguments, then those macros below will map all
+ * debug statements to the logging interfaces declared in syslog.h.
+ *
+ * If the cross-compiler's pre-processor does not support variable length
* arguments, then these additional APIs will be built.
*/
diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h
index 327bf37ca..93ca2a334 100644
--- a/nuttx/include/nuttx/fs/fs.h
+++ b/nuttx/include/nuttx/fs/fs.h
@@ -240,7 +240,6 @@ struct file
struct filelist
{
sem_t fl_sem; /* Manage access to the file list */
- int16_t fl_crefs; /* Reference count */
struct file fl_files[CONFIG_NFILE_DESCRIPTORS];
};
#endif
@@ -294,7 +293,6 @@ struct file_struct
struct streamlist
{
- int sl_crefs; /* Reference count */
sem_t sl_sem; /* For thread safety */
struct file_struct sl_streams[CONFIG_NFILE_STREAMS];
};
@@ -318,7 +316,8 @@ typedef int (*foreach_mountpoint_t)(FAR const char *mountpoint,
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -333,7 +332,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN void weak_function fs_initialize(void);
+void weak_function fs_initialize(void);
/* fs_foreachmountpoint.c ***************************************************/
/****************************************************************************
@@ -357,7 +356,7 @@ EXTERN void weak_function fs_initialize(void);
****************************************************************************/
#ifndef CONFIG_DISABLE_MOUNTPOUNT
-EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg);
+int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg);
#endif
/* fs_registerdriver.c ******************************************************/
@@ -384,9 +383,8 @@ EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg);
*
****************************************************************************/
-EXTERN int register_driver(const char *path,
- const struct file_operations *fops,
- mode_t mode, void *priv);
+int register_driver(FAR const char *path, FAR const struct file_operations *fops,
+ mode_t mode, FAR void *priv);
/* fs_registerblockdriver.c *************************************************/
/****************************************************************************
@@ -412,9 +410,9 @@ EXTERN int register_driver(const char *path,
*
****************************************************************************/
-EXTERN int register_blockdriver(const char *path,
- const struct block_operations *bops,
- mode_t mode, void *priv);
+int register_blockdriver(FAR const char *path,
+ FAR const struct block_operations *bops, mode_t mode,
+ FAR void *priv);
/* fs_unregisterdriver.c ****************************************************/
/****************************************************************************
@@ -425,7 +423,7 @@ EXTERN int register_blockdriver(const char *path,
*
****************************************************************************/
-EXTERN int unregister_driver(const char *path);
+int unregister_driver(const char *path);
/* fs_unregisterblockdriver.c ***********************************************/
/****************************************************************************
@@ -436,7 +434,7 @@ EXTERN int unregister_driver(const char *path);
*
****************************************************************************/
-EXTERN int unregister_blockdriver(const char *path);
+int unregister_blockdriver(const char *path);
/* fs_open.c ****************************************************************/
/****************************************************************************
@@ -447,30 +445,19 @@ EXTERN int unregister_blockdriver(const char *path);
*
****************************************************************************/
-EXTERN int inode_checkflags(FAR struct inode *inode, int oflags);
+int inode_checkflags(FAR struct inode *inode, int oflags);
/* fs_files.c ***************************************************************/
/****************************************************************************
- * Name: files_alloclist
- *
- * Description: Allocate a list of files for a new task
- *
- ****************************************************************************/
-
-#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN FAR struct filelist *files_alloclist(void);
-#endif
-
-/****************************************************************************
- * Name: files_addreflist
+ * Name: files_initlist
*
* Description:
- * Increase the reference count on a file list
+ * Initializes the list of files for a new task
*
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int files_addreflist(FAR struct filelist *list);
+void files_initlist(FAR struct filelist *list);
#endif
/****************************************************************************
@@ -482,7 +469,7 @@ EXTERN int files_addreflist(FAR struct filelist *list);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int files_releaselist(FAR struct filelist *list);
+void files_releaselist(FAR struct filelist *list);
#endif
/****************************************************************************
@@ -495,7 +482,7 @@ EXTERN int files_releaselist(FAR struct filelist *list);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2);
+int files_dup(FAR struct file *filep1, FAR struct file *filep2);
#endif
/* fs_filedup.c *************************************************************/
@@ -515,7 +502,7 @@ EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int file_dup(int fd, int minfd);
+int file_dup(int fd, int minfd);
#endif
/* fs_filedup2.c ************************************************************/
@@ -535,7 +522,7 @@ EXTERN int file_dup(int fd, int minfd);
#if CONFIG_NFILE_DESCRIPTORS > 0
#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
-EXTERN int file_dup2(int fd1, int fd2);
+int file_dup2(int fd1, int fd2);
#else
# define file_dup2(fd1, fd2) dup2(fd1, fd2)
#endif
@@ -566,8 +553,8 @@ EXTERN int file_dup2(int fd1, int fd2);
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int open_blockdriver(FAR const char *pathname, int mountflags,
- FAR struct inode **ppinode);
+int open_blockdriver(FAR const char *pathname, int mountflags,
+ FAR struct inode **ppinode);
#endif
/* fs_closeblockdriver.c ****************************************************/
@@ -589,7 +576,7 @@ EXTERN int open_blockdriver(FAR const char *pathname, int mountflags,
****************************************************************************/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int close_blockdriver(FAR struct inode *inode);
+int close_blockdriver(FAR struct inode *inode);
#endif
/* fs_fdopen.c **************************************************************/
@@ -609,7 +596,7 @@ typedef struct _TCB _TCB;
#define __TCB_DEFINED__
#endif
-EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
+FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
#endif
/* lib/stdio/lib_fflush.c **************************************************/
@@ -623,7 +610,7 @@ EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb);
****************************************************************************/
#if CONFIG_NFILE_STREAMS > 0
-EXTERN int lib_flushall(FAR struct streamlist *list);
+int lib_flushall(FAR struct streamlist *list);
#endif
/* drivers/dev_null.c *******************************************************/
@@ -635,7 +622,7 @@ EXTERN int lib_flushall(FAR struct streamlist *list);
*
****************************************************************************/
-EXTERN void devnull_register(void);
+void devnull_register(void);
/* drivers/dev_zero.c *******************************************************/
/****************************************************************************
@@ -646,7 +633,7 @@ EXTERN void devnull_register(void);
*
****************************************************************************/
-EXTERN void devzero_register(void);
+void devzero_register(void);
/* drivers/loop.c ***********************************************************/
/****************************************************************************
@@ -658,8 +645,8 @@ EXTERN void devzero_register(void);
*
****************************************************************************/
-EXTERN int losetup(FAR const char *devname, FAR const char *filename,
- uint16_t sectsize, off_t offset, bool readonly);
+int losetup(FAR const char *devname, FAR const char *filename,
+ uint16_t sectsize, off_t offset, bool readonly);
/****************************************************************************
* Name: loteardown
@@ -669,7 +656,7 @@ EXTERN int losetup(FAR const char *devname, FAR const char *filename,
*
****************************************************************************/
-EXTERN int loteardown(FAR const char *devname);
+int loteardown(FAR const char *devname);
/* drivers/bch/bchdev_register.c ********************************************/
/****************************************************************************
@@ -681,8 +668,8 @@ EXTERN int loteardown(FAR const char *devname);
*
****************************************************************************/
-EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev,
- bool readonly);
+int bchdev_register(FAR const char *blkdev, FAR const char *chardev,
+ bool readonly);
/* drivers/bch/bchdev_unregister.c ******************************************/
/****************************************************************************
@@ -694,7 +681,7 @@ EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev,
*
****************************************************************************/
-EXTERN int bchdev_unregister(FAR const char *chardev);
+int bchdev_unregister(FAR const char *chardev);
/* Low level, direct access. NOTE: low-level access and character driver access
* are incompatible. One and only one access method should be implemented.
@@ -710,8 +697,7 @@ EXTERN int bchdev_unregister(FAR const char *chardev);
*
****************************************************************************/
-EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly,
- FAR void **handle);
+int bchlib_setup(FAR const char *blkdev, bool readonly, FAR void **handle);
/* drivers/bch/bchlib_teardown.c ********************************************/
/****************************************************************************
@@ -723,7 +709,7 @@ EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly,
*
****************************************************************************/
-EXTERN int bchlib_teardown(FAR void *handle);
+int bchlib_teardown(FAR void *handle);
/* drivers/bch/bchlib_read.c ************************************************/
/****************************************************************************
@@ -735,8 +721,8 @@ EXTERN int bchlib_teardown(FAR void *handle);
*
****************************************************************************/
-EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset,
- size_t len);
+ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset,
+ size_t len);
/* drivers/bch/bchlib_write.c ***********************************************/
/****************************************************************************
@@ -748,8 +734,8 @@ EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset,
*
****************************************************************************/
-EXTERN ssize_t bchlib_write(FAR void *handle, FAR const char *buffer,
- size_t offset, size_t len);
+ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, size_t offset,
+ size_t len);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/lib.h b/nuttx/include/nuttx/lib.h
index 220af2030..3bc581e18 100644
--- a/nuttx/include/nuttx/lib.h
+++ b/nuttx/include/nuttx/lib.h
@@ -2,7 +2,7 @@
* include/nuttx/lib.h
* Non-standard, internal APIs available in lib/.
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -67,11 +67,10 @@ extern "C" {
/* Functions contained in lib_init.c ****************************************/
-EXTERN void weak_function lib_initialize(void);
+void weak_function lib_initialize(void);
#if CONFIG_NFILE_STREAMS > 0
-EXTERN FAR struct streamlist *lib_alloclist(void);
-EXTERN void lib_addreflist(FAR struct streamlist *list);
-EXTERN void lib_releaselist(FAR struct streamlist *list);
+void lib_streaminit(FAR struct streamlist *list);
+void lib_releaselist(FAR struct streamlist *list);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/net/net.h b/nuttx/include/nuttx/net/net.h
index b79dda755..d23fb8796 100644
--- a/nuttx/include/nuttx/net/net.h
+++ b/nuttx/include/nuttx/net/net.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/net/net.h
*
- * Copyright (C) 2007, 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -106,7 +106,6 @@ struct socket
struct socketlist
{
sem_t sl_sem; /* Manage access to the socket list */
- int16_t sl_crefs; /* Reference count */
struct socket sl_sockets[CONFIG_NSOCKET_DESCRIPTORS];
};
#endif
@@ -117,110 +116,114 @@ struct uip_driver_s; /* Forward reference. See nuttx/net/uip/uip-arch.h */
typedef int (*netdev_callback_t)(FAR struct uip_driver_s *dev, void *arg);
/****************************************************************************
- * Public Function Prototypes
+ * Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
/* net_checksd.c *************************************************************/
/* Check if the socket descriptor is valid for the provided TCB and if it
* supports the requested access.
*/
-EXTERN int net_checksd(int fd, int oflags);
+int net_checksd(int fd, int oflags);
/* net_sockets.c *************************************************************/
/* There interfaces are called only from OS scheduling and iniialization logic
* under sched/
*/
-EXTERN void weak_function net_initialize(void);
-EXTERN FAR struct socketlist *net_alloclist(void);
-EXTERN int net_addreflist(FAR struct socketlist *list);
-EXTERN int net_releaselist(FAR struct socketlist *list);
+void weak_function net_initialize(void);
+void net_initlist(FAR struct socketlist *list);
+void net_releaselist(FAR struct socketlist *list);
/* Given a socket descriptor, return the underly NuttX-specific socket
* structure.
*/
-EXTERN FAR struct socket *sockfd_socket(int sockfd);
+FAR struct socket *sockfd_socket(int sockfd);
/* socket.c ******************************************************************/
/* socket using underlying socket structure */
-EXTERN int psock_socket(int domain, int type, int protocol,
- FAR struct socket *psock);
+int psock_socket(int domain, int type, int protocol, FAR struct socket *psock);
/* net_close.c ***************************************************************/
/* The standard close() operation redirects operations on socket descriptors
* to this function.
*/
-EXTERN int net_close(int sockfd);
+int net_close(int sockfd);
/* Performs the close operation on a socket instance */
-EXTERN int psock_close(FAR struct socket *psock);
+int psock_close(FAR struct socket *psock);
/* net_close.c ***************************************************************/
/* Performs the bind() operation on a socket instance */
-EXTERN int psock_bind(FAR struct socket *psock,
- FAR const struct sockaddr *addr, socklen_t addrlen);
+int psock_bind(FAR struct socket *psock, FAR const struct sockaddr *addr,
+ socklen_t addrlen);
/* connect.c *****************************************************************/
/* Performs the connect() operation on a socket instance */
-EXTERN int psock_connect(FAR struct socket *psock,
- FAR const struct sockaddr *addr, socklen_t addrlen);
+int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr,
+ socklen_t addrlen);
/* send.c ********************************************************************/
/* Send using underlying socket structure */
-EXTERN ssize_t psock_send(FAR struct socket *psock, const void *buf,
- size_t len, int flags);
+ssize_t psock_send(FAR struct socket *psock, const void *buf, size_t len,
+ int flags);
/* sendto.c ******************************************************************/
/* Sendto using underlying socket structure */
-EXTERN ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
- size_t len, int flags, FAR const struct sockaddr *to,
- socklen_t tolen);
+ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf,
+ size_t len, int flags, FAR const struct sockaddr *to,
+ socklen_t tolen);
/* recvfrom.c ****************************************************************/
/* recvfrom using the underlying socket structure */
-EXTERN ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf,
- size_t len, int flags,FAR struct sockaddr *from,
- FAR socklen_t *fromlen);
+ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
+ int flags,FAR struct sockaddr *from,
+ FAR socklen_t *fromlen);
/* recv using the underlying socket structure */
-#define psock_recv(psock,buf,len,flags) psock_recvfrom(psock,buf,len,flags,NULL,0)
+#define psock_recv(psock,buf,len,flags) \
+ psock_recvfrom(psock,buf,len,flags,NULL,0)
/* getsockopt.c **************************************************************/
/* getsockopt using the underlying socket structure */
-EXTERN int psock_getsockopt(FAR struct socket *psock, int level, int option,
- FAR void *value, FAR socklen_t *value_len);
+int psock_getsockopt(FAR struct socket *psock, int level, int option,
+ FAR void *value, FAR socklen_t *value_len);
/* setsockopt.c **************************************************************/
/* setsockopt using the underlying socket structure */
-EXTERN int psock_setsockopt(FAR struct socket *psock, int level, int option,
- FAR const void *value, socklen_t value_len);
+int psock_setsockopt(FAR struct socket *psock, int level, int option,
+ FAR const void *value, socklen_t value_len);
/* net_ioctl.c ***************************************************************/
/* The standard ioctl() operation redirects operations on socket descriptors
* to this function.
*/
-EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
+int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
/* net_poll.c ****************************************************************/
/* The standard poll() operation redirects operations on socket descriptors
@@ -229,7 +232,9 @@ EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg);
#ifndef CONFIG_DISABLE_POLL
struct pollfd; /* Forward reference -- see poll.h */
-EXTERN int net_poll(int sockfd, struct pollfd *fds, bool setup);
+
+int psock_poll(FAR struct socket *psock, struct pollfd *fds, bool setup);
+int net_poll(int sockfd, struct pollfd *fds, bool setup);
#endif
/* net_dup.c *****************************************************************/
@@ -237,7 +242,7 @@ EXTERN int net_poll(int sockfd, struct pollfd *fds, bool setup);
* this function
*/
-EXTERN int net_dup(int sockfd, int minsd);
+int net_dup(int sockfd, int minsd);
/* net_dup2.c ****************************************************************/
/* The standard dup2() operation redirects operations on socket descriptors to
@@ -245,7 +250,7 @@ EXTERN int net_dup(int sockfd, int minsd);
*/
#if CONFIG_NFILE_DESCRIPTORS > 0
-EXTERN int net_dup2(int sockfd1, int sockfd2);
+int net_dup2(int sockfd1, int sockfd2);
#else
# define net_dup2(sockfd1, sockfd2) dup2(sockfd1, sockfd2)
#endif
@@ -253,12 +258,12 @@ EXTERN int net_dup2(int sockfd1, int sockfd2);
/* net_clone.c ***************************************************************/
/* Performs the low level, common portion of net_dup() and net_dup2() */
-EXTERN int net_clone(FAR struct socket *psock1, FAR struct socket *psock2);
+int net_clone(FAR struct socket *psock1, FAR struct socket *psock2);
/* net_vfcntl.c **************************************************************/
/* Performs fcntl operations on socket */
-EXTERN int net_vfcntl(int sockfd, int cmd, va_list ap);
+int net_vfcntl(int sockfd, int cmd, va_list ap);
/* netdev-register.c *********************************************************/
/* This function is called by network interface device drivers to inform the
@@ -267,23 +272,23 @@ EXTERN int net_vfcntl(int sockfd, int cmd, va_list ap);
* addresses
*/
-EXTERN int netdev_register(FAR struct uip_driver_s *dev);
+int netdev_register(FAR struct uip_driver_s *dev);
/* netdev-unregister.c *********************************************************/
/* Unregister a network device driver. */
-EXTERN int netdev_unregister(FAR struct uip_driver_s *dev);
+int netdev_unregister(FAR struct uip_driver_s *dev);
/* net_foreach.c ************************************************************/
/* Enumerates all registered network devices */
-EXTERN int netdev_foreach(netdev_callback_t callback, void *arg);
+int netdev_foreach(netdev_callback_t callback, void *arg);
/* drivers/net/slip.c ******************************************************/
/* Instantiate a SLIP network interface. */
#ifdef CONFIG_NET_SLIP
-EXTERN int slip_initialize(int intf, const char *devname);
+int slip_initialize(int intf, const char *devname);
#endif
#undef EXTERN
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 1e75b5020..f8b4eb0dc 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -52,19 +52,55 @@
#include <time.h>
#include <nuttx/irq.h>
+#include <nuttx/fs/fs.h>
#include <nuttx/net/net.h>
/********************************************************************************
* Pre-processor Definitions
********************************************************************************/
+/* Configuration ****************************************************************/
+/* Task groups currently only supported for retention of child status */
-/* Task Management Definitins ***************************************************/
+#undef HAVE_TASK_GROUP
+#undef HAVE_GROUP_MEMBERS
+
+/* We need a group an group members if we are supportint the parent/child
+ * relationship.
+ */
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+# define HAVE_TASK_GROUP 1
+# define HAVE_GROUP_MEMBERS 1
+
+/* We need a group (but not members) if any other resources are shared within
+ * a task group.
+ */
+
+#else
+# if !defined(CONFIG_DISABLE_ENVIRON)
+# define HAVE_TASK_GROUP 1
+# elif CONFIG_NFILE_DESCRIPTORS > 0
+# define HAVE_TASK_GROUP 1
+# elif CONFIG_NFILE_STREAMS > 0
+# define HAVE_TASK_GROUP 1
+# elif CONFIG_NSOCKET_DESCRIPTORS > 0
+# define HAVE_TASK_GROUP 1
+# endif
+#endif
+
+/* In any event, we don't need group members if support for pthreads is disabled */
+
+#ifdef CONFIG_DISABLE_PTHREAD
+# undef HAVE_GROUP_MEMBERS
+#endif
+
+/* Task Management Definitions **************************************************/
/* This is the maximum number of times that a lock can be set */
#define MAX_LOCK_COUNT 127
-/* Values for the _TCB flags flag bits */
+/* Values for the _TCB flags bits */
#define TCB_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: thread type */
#define TCB_FLAG_TTYPE_MASK (3 << TCB_FLAG_TTYPE_SHIFT)
@@ -74,7 +110,11 @@
#define TCB_FLAG_NONCANCELABLE (1 << 2) /* Bit 2: Pthread is non-cancelable */
#define TCB_FLAG_CANCEL_PENDING (1 << 3) /* Bit 3: Pthread cancel is pending */
#define TCB_FLAG_ROUND_ROBIN (1 << 4) /* Bit 4: Round robin sched enabled */
-#define TCB_FLAG_NOCLDWAIT (1 << 5) /* Bit 5: Do not retain child exit status */
+#define TCB_FLAG_EXIT_PROCESSING (1 << 5) /* Bit 5: Exitting */
+
+/* Values for struct task_group tg_flags */
+
+#define GROUP_FLAG_NOCLDWAIT (1 << 0) /* Bit 0: Do not retain child exit status */
/* Values for struct child_status_s ch_flags */
@@ -143,7 +183,13 @@ union entry_u
};
typedef union entry_u entry_t;
-/* These is the types of the functions that are executed with exit() is called
+/* This is the type of the function called at task startup */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+typedef CODE void (*starthook_t)(FAR void *arg);
+#endif
+
+/* These are the types of the functions that are executed with exit() is called
* (if registered via atexit() on on_exit()).
*/
@@ -159,20 +205,7 @@ typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg);
typedef struct msgq_s msgq_t;
-/* The structure used to maintain environment variables */
-
-#ifndef CONFIG_DISABLE_ENVIRON
-struct environ_s
-{
- unsigned int ev_crefs; /* Reference count used when environment
- * is shared by threads */
- size_t ev_alloc; /* Number of bytes allocated in environment */
- char ev_env[1]; /* Environment strings */
-};
-typedef struct environ_s environ_t;
-# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1)
-#endif
-
+/* struct child_status_s *********************************************************/
/* This structure is used to maintin information about child tasks.
* pthreads work differently, they have join information. This is
* only for child tasks.
@@ -189,6 +222,7 @@ struct child_status_s
};
#endif
+/* struct dspace_s ***************************************************************/
/* This structure describes a reference counted D-Space region. This must be a
* separately allocated "break-away" structure that can be owned by a task and
* any pthreads created by the task.
@@ -214,6 +248,88 @@ struct dspace_s
};
#endif
+/* struct task_group_s ***********************************************************/
+/* All threads created by pthread_create belong in the same task group (along with
+ * the thread of the original task). struct task_group_s is a shared, "breakaway"
+ * structure referenced by each TCB.
+ *
+ * This structure should contain *all* resources shared by tasks and threads that
+ * belong to the same task group:
+ *
+ * Child exit status
+ * Environment varibles
+ * PIC data space and address environments
+ * File descriptors
+ * FILE streams
+ * Sockets
+ *
+ * Currenty, however, this implementation only applies to child exit status.
+ *
+ * Each instance of struct task_group_s is reference counted. Each instance is
+ * created with a reference count of one. The reference incremeneted when each
+ * thread joins the group and decremented when each thread exits, leaving the
+ * group. When the refernce count decrements to zero, the struc task_group_s
+ * is free.
+ */
+
+#ifdef HAVE_TASK_GROUP
+struct task_group_s
+{
+#ifdef HAVE_GROUP_MEMBERS
+ struct task_group_s *flink; /* Supports a singly linked list */
+ gid_t tg_gid; /* The ID of this task group */
+ gid_t tg_pgid; /* The ID of the parent task group */
+#endif
+ uint8_t tg_flags; /* See GROUP_FLAG_* definitions */
+
+ /* Group membership ***********************************************************/
+
+ uint8_t tg_nmembers; /* Number of members in the group */
+#ifdef HAVE_GROUP_MEMBERS
+ uint8_t tg_mxmembers; /* Number of members in allocation */
+ FAR pid_t *tg_members; /* Members of the group */
+#endif
+
+ /* Child exit status **********************************************************/
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+ FAR struct child_status_s *tg_children; /* Head of a list of child status */
+#endif
+
+ /* Environment variables ******************************************************/
+
+#ifndef CONFIG_DISABLE_ENVIRON
+ size_t tg_envsize; /* Size of environment string allocation */
+ FAR char *tg_envp; /* Allocated environment strings */
+#endif
+
+ /* PIC data space and address environments ************************************/
+ /* Logically the PIC data space belongs here (see struct dspace_s). The
+ * current logic needs review: There are differences in the away that the
+ * life of the PIC data is managed.
+ */
+
+ /* File descriptors ***********************************************************/
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ struct filelist tg_filelist; /* Maps file descriptor to file */
+#endif
+
+ /* FILE streams ***************************************************************/
+
+#if CONFIG_NFILE_STREAMS > 0
+ struct streamlist tg_streamlist; /* Holds C buffered I/O info */
+#endif /* CONFIG_NFILE_STREAMS */
+
+ /* Sockets ********************************************************************/
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ struct socketlist tg_socketlist; /* Maps socket descriptor to socket */
+#endif
+};
+#endif
+
+/* _TCB **************************************************************************/
/* This is the task control block (TCB). Each task or thread is represented by
* a TCB. The TCB is the heart of the NuttX task-control logic.
*/
@@ -225,20 +341,33 @@ struct _TCB
FAR struct _TCB *flink; /* Doubly linked list */
FAR struct _TCB *blink;
+ /* Task Group *****************************************************************/
+
+#ifdef HAVE_TASK_GROUP
+ FAR struct task_group_s *group; /* Pointer to shared task group data */
+#endif
+
/* Task Management Fields *****************************************************/
pid_t pid; /* This is the ID of the thread */
+
#ifdef CONFIG_SCHED_HAVE_PARENT /* Support parent-child relationship */
- pid_t parent; /* This is the ID of the parent thread */
-#ifdef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */
- FAR struct child_status_s *children; /* Head of a list of child status */
-#else
+#ifndef HAVE_GROUP_MEMBERS /* Don't know pids of group members */
+ pid_t ppid; /* This is the ID of the parent thread */
+#ifndef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */
uint16_t nchildren; /* This is the number active children */
#endif
#endif
+#endif /* CONFIG_SCHED_HAVE_PARENT */
+
start_t start; /* Thread start function */
entry_t entry; /* Entry Point into the thread */
+#ifdef CONFIG_SCHED_STARTHOOK
+ starthook_t starthook; /* Task startup function */
+ FAR void *starthookarg; /* The argument passed to the function */
+#endif
+
#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT)
# if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1
atexitfunc_t atexitfunc[CONFIG_SCHED_ATEXIT_MAX];
@@ -289,10 +418,6 @@ struct _TCB
uint8_t init_priority; /* Initial priority of the task */
char *argv[CONFIG_MAX_TASK_ARGS+1]; /* Name+start-up parameters */
-#ifndef CONFIG_DISABLE_ENVIRON
- FAR environ_t *envp; /* Environment variables */
-#endif
-
/* Stack-Related Fields *******************************************************/
#ifndef CONFIG_CUSTOM_STACK
@@ -344,22 +469,6 @@ struct _TCB
int pterrno; /* Current per-thread errno */
- /* File system support ********************************************************/
-
-#if CONFIG_NFILE_DESCRIPTORS > 0
- FAR struct filelist *filelist; /* Maps file descriptor to file */
-#endif
-
-#if CONFIG_NFILE_STREAMS > 0
- FAR struct streamlist *streams; /* Holds C buffered I/O info */
-#endif
-
- /* Network socket *************************************************************/
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- FAR struct socketlist *sockets; /* Maps file descriptor to file */
-#endif
-
/* State save areas ***********************************************************/
/* The form and content of these fields are processor-specific. */
@@ -421,6 +530,12 @@ FAR struct streamlist *sched_getstreams(void);
FAR struct socketlist *sched_getsockets(void);
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+/* Setup up a start hook */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg);
+#endif
+
/* Internal vfork support.The overall sequence is:
*
* 1) User code calls vfork(). vfork() is provided in architecture-specific
diff --git a/nuttx/include/nuttx/serial/serial.h b/nuttx/include/nuttx/serial/serial.h
index 49dba3795..4ee2005ef 100644
--- a/nuttx/include/nuttx/serial/serial.h
+++ b/nuttx/include/nuttx/serial/serial.h
@@ -1,7 +1,7 @@
/************************************************************************************
* include/nuttx/serial/serial.h
*
- * Copyright (C) 2007-2008, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,6 +49,7 @@
#ifdef CONFIG_SERIAL_TERMIOS
# include <termios.h>
#endif
+
#include <nuttx/fs/fs.h>
/************************************************************************************
@@ -193,20 +194,23 @@ struct uart_ops_s
struct uart_dev_s
{
- uint8_t open_count; /* Number of times the device has been opened */
- volatile bool xmitwaiting; /* true: User waiting for space in xmit.buffer */
- volatile bool recvwaiting; /* true: User waiting for data in recv.buffer */
- bool isconsole; /* true: This is the serial console */
- sem_t closesem; /* Locks out new open while close is in progress */
- sem_t xmitsem; /* Wakeup user waiting for space in xmit.buffer */
- sem_t recvsem; /* Wakeup user waiting for data in recv.buffer */
+ uint8_t open_count; /* Number of times the device has been opened */
+ volatile bool xmitwaiting; /* true: User waiting for space in xmit.buffer */
+ volatile bool recvwaiting; /* true: User waiting for data in recv.buffer */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ volatile bool disconnected; /* true: Removable device is not connected */
+#endif
+ bool isconsole; /* true: This is the serial console */
+ sem_t closesem; /* Locks out new open while close is in progress */
+ sem_t xmitsem; /* Wakeup user waiting for space in xmit.buffer */
+ sem_t recvsem; /* Wakeup user waiting for data in recv.buffer */
#ifndef CONFIG_DISABLE_POLL
- sem_t pollsem; /* Manages exclusive access to fds[] */
+ sem_t pollsem; /* Manages exclusive access to fds[] */
#endif
- struct uart_buffer_s xmit; /* Describes transmit buffer */
- struct uart_buffer_s recv; /* Describes receive buffer */
- FAR const struct uart_ops_s *ops; /* Arch-specific operations */
- FAR void *priv; /* Used by the arch-specific logic */
+ struct uart_buffer_s xmit; /* Describes transmit buffer */
+ struct uart_buffer_s recv; /* Describes receive buffer */
+ FAR const struct uart_ops_s *ops; /* Arch-specific operations */
+ FAR void *priv; /* Used by the arch-specific logic */
/* The following is a list if poll structures of threads waiting for
* driver events. The 'struct pollfd' reference for each open is also
@@ -226,25 +230,27 @@ struct uart_dev_s
#endif
};
+
typedef struct uart_dev_s uart_dev_t;
/************************************************************************************
* Public Data
************************************************************************************/
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
* Name: uart_register
*
* Description:
@@ -252,7 +258,7 @@ extern "C" {
*
************************************************************************************/
-EXTERN int uart_register(FAR const char *path, FAR uart_dev_t *dev);
+int uart_register(FAR const char *path, FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_xmitchars
@@ -265,7 +271,7 @@ EXTERN int uart_register(FAR const char *path, FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_xmitchars(FAR uart_dev_t *dev);
+void uart_xmitchars(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_receivechars
@@ -278,7 +284,7 @@ EXTERN void uart_xmitchars(FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_recvchars(FAR uart_dev_t *dev);
+void uart_recvchars(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_datareceived
@@ -290,7 +296,7 @@ EXTERN void uart_recvchars(FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_datareceived(FAR uart_dev_t *dev);
+void uart_datareceived(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_datasent
@@ -303,7 +309,31 @@ EXTERN void uart_datareceived(FAR uart_dev_t *dev);
*
************************************************************************************/
-EXTERN void uart_datasent(FAR uart_dev_t *dev);
+void uart_datasent(FAR uart_dev_t *dev);
+
+/************************************************************************************
+ * Name: uart_connected
+ *
+ * Description:
+ * Serial devices (like USB serial) can be removed. In that case, the "upper
+ * half" serial driver must be informed that there is no longer a valid serial
+ * channel associated with the driver.
+ *
+ * In this case, the driver will terminate all pending transfers wint ENOTCONN and
+ * will refuse all further transactions while the "lower half" is disconnected.
+ * The driver will continue to be registered, but will be in an unusable state.
+ *
+ * Conversely, the "upper half" serial driver needs to know when the serial
+ * device is reconnected so that it can resume normal operations.
+ *
+ * Assumptions/Limitations:
+ * This function may be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+void uart_connected(FAR uart_dev_t *dev, bool connected);
+#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/syslog.h b/nuttx/include/nuttx/syslog.h
index 3c340d23a..bb3c8f493 100644
--- a/nuttx/include/nuttx/syslog.h
+++ b/nuttx/include/nuttx/syslog.h
@@ -116,10 +116,10 @@ EXTERN int syslog_initialize(void);
*
* Description:
* This is the low-level system logging interface. The debugging/syslogging
- * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is
- * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses
+ * interfaces are syslog() and lowsyslog(). The difference is that
+ * the syslog() internface writes to fd=1 (stdout) whereas lowsyslog() uses
* a lower level interface that works from interrupt handlers. This
- * function is a a low-level interface used to implement lib_lowprintf().
+ * function is a a low-level interface used to implement lowsyslog().
*
****************************************************************************/
diff --git a/nuttx/include/nuttx/usb/cdcacm.h b/nuttx/include/nuttx/usb/cdcacm.h
index 1dca050c4..49dc4ee12 100644
--- a/nuttx/include/nuttx/usb/cdcacm.h
+++ b/nuttx/include/nuttx/usb/cdcacm.h
@@ -54,7 +54,7 @@
* Endpoint 0 max packet size. Default 64.
* CONFIG_CDCACM_EPINTIN
* The logical 7-bit address of a hardware endpoint that supports
- * interrupt IN operation. Default 2.
+ * interrupt IN operation. Default 1.
* CONFIG_CDCACM_EPINTIN_FSSIZE
* Max package size for the interrupt IN endpoint if full speed mode.
* Default 64.
@@ -63,7 +63,7 @@
* Default 64.
* CONFIG_CDCACM_EPBULKOUT
* The logical 7-bit address of a hardware endpoint that supports
- * bulk OUT operation
+ * bulk OUT operation. Default: 3
* CONFIG_CDCACM_EPBULKOUT_FSSIZE
* Max package size for the bulk OUT endpoint if full speed mode.
* Default 64.
@@ -72,7 +72,7 @@
* Default 512.
* CONFIG_CDCACM_EPBULKIN
* The logical 7-bit address of a hardware endpoint that supports
- * bulk IN operation
+ * bulk IN operation. Default: 2
* CONFIG_CDCACM_EPBULKIN_FSSIZE
* Max package size for the bulk IN endpoint if full speed mode.
* Default 64.
@@ -107,7 +107,7 @@
*/
#ifndef CONFIG_CDCACM_EPINTIN
-# define CONFIG_CDCACM_EPINTIN 2
+# define CONFIG_CDCACM_EPINTIN 1
#endif
#ifndef CONFIG_CDCACM_EPINTIN_FSSIZE
@@ -124,7 +124,7 @@
*/
#ifndef CONFIG_CDCACM_EPBULKIN
-# define CONFIG_CDCACM_EPBULKIN 3
+# define CONFIG_CDCACM_EPBULKIN 2
#endif
#ifndef CONFIG_CDCACM_EPBULKIN_FSSIZE
@@ -141,7 +141,7 @@
*/
#ifndef CONFIG_CDCACM_EPBULKOUT
-# define CONFIG_CDCACM_EPBULKOUT 4
+# define CONFIG_CDCACM_EPBULKOUT 3
#endif
#ifndef CONFIG_CDCACM_EPBULKOUT_FSSIZE
diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
index ab3a5f4be..860f48983 100644
--- a/nuttx/include/nuttx/usb/usbdev_trace.h
+++ b/nuttx/include/nuttx/usb/usbdev_trace.h
@@ -104,6 +104,7 @@
#define TRACE_DEVUNINIT TRACE_EVENT(TRACE_INIT_ID, 0x0002)
#define TRACE_DEVREGISTER TRACE_EVENT(TRACE_INIT_ID, 0x0003)
#define TRACE_DEVUNREGISTER TRACE_EVENT(TRACE_INIT_ID, 0x0004)
+#define TRACE_DEVINIT_USER TRACE_EVENT(TRACE_INIT_ID, 0x0005) /* First user-defined */
/* API calls (see usbdev.h) */
@@ -117,6 +118,7 @@
#define TRACE_EPCANCEL TRACE_EVENT(TRACE_EP_ID, 0x0008)
#define TRACE_EPSTALL TRACE_EVENT(TRACE_EP_ID, 0x0009)
#define TRACE_EPRESUME TRACE_EVENT(TRACE_EP_ID, 0x000a)
+#define TRACE_EPAPI_USER TRACE_EVENT(TRACE_EP_ID, 0x000b) /* First user-defined */
#define TRACE_DEVALLOCEP TRACE_EVENT(TRACE_DEV_ID, 0x0001)
#define TRACE_DEVFREEEP TRACE_EVENT(TRACE_DEV_ID, 0x0002)
@@ -124,6 +126,7 @@
#define TRACE_DEVWAKEUP TRACE_EVENT(TRACE_DEV_ID, 0x0004)
#define TRACE_DEVSELFPOWERED TRACE_EVENT(TRACE_DEV_ID, 0x0005)
#define TRACE_DEVPULLUP TRACE_EVENT(TRACE_DEV_ID, 0x0006)
+#define TRACE_DEVAPI_USER TRACE_EVENT(TRACE_DEV_ID, 0x0007) /* First user-defined */
#define TRACE_CLASSBIND TRACE_EVENT(TRACE_CLASS_ID, 0x0001)
#define TRACE_CLASSUNBIND TRACE_EVENT(TRACE_CLASS_ID, 0x0002)
@@ -135,6 +138,8 @@
#define TRACE_CLASSRDCOMPLETE TRACE_EVENT(TRACE_CLASS_ID, 0x0007)
#define TRACE_CLASSWRCOMPLETE TRACE_EVENT(TRACE_CLASS_ID, 0x0008)
+#define TRACE_CLASSAPI_USER TRACE_EVENT(TRACE_CLASS_ID, 0x0009) /* First user-defined */
+
#define TRACE_CLASSAPI(id) TRACE_EVENT(TRACE_CLASSAPI_ID, id)
#define TRACE_CLASSSTATE(id) TRACE_EVENT(TRACE_CLASSSTATE_ID, id)
diff --git a/nuttx/sched/env_share.c b/nuttx/include/syslog.h
index 5f37a0219..cfb2db97b 100644
--- a/nuttx/sched/env_share.c
+++ b/nuttx/include/syslog.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/env_share.c
+ * include/syslog.h
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,85 +33,62 @@
*
****************************************************************************/
+#ifndef __INCLUDE_SYSLOG_H
+#define __INCLUDE_SYSLOG_H
+
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
-#ifndef CONFIG_DISABLE_ENVIRON
-
-#include <sched.h>
-#include <errno.h>
+#include <stdint.h>
+#include <stdarg.h>
-#include "os_internal.h"
-#include "env_internal.h"
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
/****************************************************************************
- * Private Data
+ * Public Type Declarations
****************************************************************************/
/****************************************************************************
- * Public Functions
+ * Public Variables
****************************************************************************/
/****************************************************************************
- * Name: env_share
- *
- * Description:
- * Increment the reference count on the internal environment structure of
- * a task. This is the action that is performed when a new pthread is
- * created: The new pthread shares the environment with its parent.
- *
- * Parameters:
- * ptcb The new TCB to receive the shared environment.
- *
- * Return Value:
- * A pointer to a specified TCB's environment structure with an incremented
- * reference count.
- *
- * Assumptions:
- * Not called from an interrupt handler.
- *
+ * Public Function Prototypes
****************************************************************************/
-int env_share(FAR _TCB *ptcb)
+#if defined(__cplusplus)
+extern "C"
{
- int ret = OK;
- if (!ptcb)
- {
- ret = -EINVAL;
- }
- else
- {
- FAR _TCB *parent = (FAR _TCB*)g_readytorun.head;
- environ_t *envp = parent->envp;
-
- /* Pre-emption must be disabled throughout the following because the
- * environment is shared.
- */
-
- sched_lock();
+#endif
- /* Does the parent task have an environment? */
+/* These low-level debug APIs are provided by the NuttX library. These are
+ * normally accessed via the macros in debug.h. If the cross-compiler's
+ * C pre-processor supports a variable number of macro arguments, then those
+ * macros below will map all debug statements to one or the other of the
+ * following.
+ */
- if (envp)
- {
- /* Yes.. increment the reference count on the environment */
+int syslog(FAR const char *format, ...);
+int vsyslog(const char *src, va_list ap);
- envp->ev_crefs++;
- }
+#ifdef CONFIG_ARCH_LOWPUTC
+int lowsyslog(FAR const char *format, ...);
+int lowvsyslog(const char *src, va_list ap);
+#endif
- /* Then share the environment */
+/* Enable or disable syslog output */
- ptcb->envp = envp;
- sched_unlock();
- }
+#ifdef CONFIG_SYSLOG_ENABLE
+void syslog_enable(bool enable);
+#endif
- return ret;
+#if defined(__cplusplus)
}
+#endif
-#endif /* CONFIG_DISABLE_ENVIRON */
-
-
-
+#endif /* __INCLUDE_SYSLOG_H */
diff --git a/nuttx/libc/lib.csv b/nuttx/libc/lib.csv
index 171f64e9b..29cdf39a6 100644
--- a/nuttx/libc/lib.csv
+++ b/nuttx/libc/lib.csv
@@ -16,7 +16,6 @@
"crc32","crc32.h","","uint32_t","FAR const uint8_t *","size_t"
"crc32part","crc32.h","","uint32_t","FAR const uint8_t *","size_t","uint32_t"
"dbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG)","int","const char *","..."
-"dbg_enable","debug.h","defined(CONFIG_DEBUG_ENABLE)","void","bool"
"dirname","libgen.h","","FAR char","FAR char *"
"dq_addafter","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
"dq_addbefore","queue.h","","void","FAR dq_entry_t *","FAR dq_entry_t *","FAR dq_queue_t *"
@@ -59,11 +58,10 @@
"inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *"
"labs","stdlib.h","","long int","long int"
"lib_dumpbuffer","debug.h","","void","FAR const char *","FAR const uint8_t *","unsigned int"
-"lib_lowprintf","debug.h","","int","FAR const char *","..."
-"lib_rawprintf","debug.h","","int","FAR const char *","..."
"llabs","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long int","long long int"
"lldbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
"llvdbg","debug.h","!defined(CONFIG_CPP_HAVE_VARARGS) && defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_ARCH_LOWPUTC)","int","const char *","..."
+"lowsyslog","syslog.h","","int","FAR const char *","..."
"match","","","int","const char *","const char *"
"memccpy","string.h","","FAR void","FAR void *","FAR const void *","int c","size_t"
"memchr","string.h","","FAR void","FAR const void *","int c","size_t"
@@ -154,6 +152,8 @@
"strtoll","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","long long","const char *nptr","char **endptr","int base"
"strtoul","stdlib.h","","unsigned long","const char *","char **","int"
"strtoull","stdlib.h","defined(CONFIG_HAVE_LONG_LONG)","unsigned long long","const char *","char **","int"
+"syslog","syslog.h","","int","FAR const char *","..."
+"syslog_enable","syslog.h","defined(CONFIG_SYSLOG_ENABLE)","void","bool"
"tcflush","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int"
"tcgetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","FAR struct termios *"
"tcsetattr","termios.h","CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_SERIAL_TERMIOS)","int","int","int","FAR const struct termios *"
diff --git a/nuttx/libc/misc/lib_dbg.c b/nuttx/libc/misc/lib_dbg.c
index 5605ff828..921a4e24d 100644
--- a/nuttx/libc/misc/lib_dbg.c
+++ b/nuttx/libc/misc/lib_dbg.c
@@ -50,8 +50,8 @@
/* Debug output is initially disabled */
-#ifdef CONFIG_DEBUG_ENABLE
-bool g_dbgenable;
+#ifdef CONFIG_SYSLOG_ENABLE
+bool g_syslogenable;
#endif
/****************************************************************************
@@ -59,17 +59,17 @@ bool g_dbgenable;
****************************************************************************/
/****************************************************************************
- * Name: dbg_enable
+ * Name: syslog_enable
*
* Description:
* Enable or disable debug output.
*
****************************************************************************/
-#ifdef CONFIG_DEBUG_ENABLE
-void dbg_enable(bool enable)
+#ifdef CONFIG_SYSLOG_ENABLE
+void syslog_enable(bool enable)
{
- g_dbgenable = enable;
+ g_syslogenable = enable;
}
#endif
@@ -89,13 +89,13 @@ int dbg(const char *format, ...)
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, format);
- ret = lib_rawvprintf(format, ap);
+ ret = vsyslog(format, ap);
va_end(ap);
}
@@ -108,13 +108,13 @@ int lldbg(const char *format, ...)
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, format);
- ret = lib_lowvprintf(format, ap);
+ ret = lowvsyslog(format, ap);
va_end(ap);
}
@@ -128,13 +128,13 @@ int vdbg(const char *format, ...)
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, format);
- ret = lib_rawvprintf(format, ap);
+ ret = vsyslog(format, ap);
va_end(ap);
}
@@ -147,13 +147,13 @@ int llvdbg(const char *format, ...)
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, format);
- ret = lib_lowvprintf(format, ap);
+ ret = lowvsyslog(format, ap);
va_end(ap);
}
diff --git a/nuttx/libc/misc/lib_dumpbuffer.c b/nuttx/libc/misc/lib_dumpbuffer.c
index 52158b220..5194560fd 100644
--- a/nuttx/libc/misc/lib_dumpbuffer.c
+++ b/nuttx/libc/misc/lib_dumpbuffer.c
@@ -51,15 +51,15 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_ARCH_LOWPUTC
-# define message(format, arg...) lib_lowprintf(format, ##arg)
+# define message(format, arg...) lowsyslog(format, ##arg)
# else
-# define message(format, arg...) lib_rawprintf(format, ##arg)
+# define message(format, arg...) syslog(format, ##arg)
# endif
#else
# ifdef CONFIG_ARCH_LOWPUTC
-# define message lib_lowprintf
+# define message lowsyslog
# else
-# define message lib_rawprintf
+# define message syslog
# endif
#endif
diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c
index 6a120f7b1..434c46505 100644
--- a/nuttx/libc/misc/lib_init.c
+++ b/nuttx/libc/misc/lib_init.c
@@ -1,7 +1,7 @@
/************************************************************
* libc/misc/lib_init.c
*
- * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -76,69 +76,35 @@ void weak_const_function lib_initialize(void)
}
#if CONFIG_NFILE_STREAMS > 0
-/* The following function is called when a new TCB is allocated. It
- * creates the streamlist instance that is stored in the TCB.
+/* The following function is called when a new task is allocated. It
+ * intializes the streamlist instance that is stored in the task group.
*/
-FAR struct streamlist *lib_alloclist(void)
+void lib_streaminit(FAR struct streamlist *list)
{
- FAR struct streamlist *list;
- list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist));
- if (list)
- {
- int i;
-
- /* Start with a reference count of one */
-
- list->sl_crefs = 1;
+ int i;
- /* Initialize the list access mutex */
+ /* Initialize the list access mutex */
- (void)sem_init(&list->sl_sem, 0, 1);
+ (void)sem_init(&list->sl_sem, 0, 1);
- /* Initialize each FILE structure */
+ /* Initialize each FILE structure */
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
- {
- /* Clear the IOB */
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ /* Clear the IOB */
- memset(&list->sl_streams[i], 0, sizeof(FILE));
+ memset(&list->sl_streams[i], 0, sizeof(FILE));
- /* Indicate not opened */
+ /* Indicate not opened */
- list->sl_streams[i].fs_filedes = -1;
+ list->sl_streams[i].fs_filedes = -1;
- /* Initialize the stream semaphore to one to support one-at-
- * a-time access to private data sets.
- */
-
- lib_sem_initialize(&list->sl_streams[i]);
- }
- }
- return list;
+ /* Initialize the stream semaphore to one to support one-at-
+ * a-time access to private data sets.
+ */
-}
-
-/* This function is called when a TCB is closed (such as with
- * pthread_create(). It increases the reference count on the stream
- * list.
- */
-
-void lib_addreflist(FAR struct streamlist *list)
-{
- if (list)
- {
- /* Increment the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register irqstate_t flags = irqsave();
- list->sl_crefs++;
- irqrestore(flags);
+ lib_sem_initialize(&list->sl_streams[i]);
}
}
@@ -149,57 +115,33 @@ void lib_addreflist(FAR struct streamlist *list)
void lib_releaselist(FAR struct streamlist *list)
{
- int crefs;
- if (list)
- {
- /* Decrement the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register irqstate_t flags = irqsave();
- crefs = --(list->sl_crefs);
- irqrestore(flags);
-
- /* If the count decrements to zero, then there is no reference
- * to the structure and it should be deallocated. Since there
- * are references, it would be an error if any task still held
- * a reference to the list's semaphore.
- */
-
- if (crefs <= 0)
- {
#if CONFIG_STDIO_BUFFER_SIZE > 0
- int i;
+ int i;
#endif
- /* Destroy the semaphore and release the filelist */
- (void)sem_destroy(&list->sl_sem);
+ DEBUGASSERT(list);
+
+ /* Destroy the semaphore and release the filelist */
- /* Release each stream in the list */
+ (void)sem_destroy(&list->sl_sem);
+
+ /* Release each stream in the list */
#if CONFIG_STDIO_BUFFER_SIZE > 0
- for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
- {
- /* Destroy the semaphore that protects the IO buffer */
-
- (void)sem_destroy(&list->sl_streams[i].fs_sem);
-
- /* Release the IO buffer */
- if (list->sl_streams[i].fs_bufstart)
- {
- sched_free(list->sl_streams[i].fs_bufstart);
- }
- }
-#endif
- /* Finally, release the list itself */
+ for (i = 0; i < CONFIG_NFILE_STREAMS; i++)
+ {
+ /* Destroy the semaphore that protects the IO buffer */
- sched_free(list);
- }
- }
+ (void)sem_destroy(&list->sl_streams[i].fs_sem);
+
+ /* Release the IO buffer */
+
+ if (list->sl_streams[i].fs_bufstart)
+ {
+ sched_free(list->sl_streams[i].fs_bufstart);
+ }
+ }
+#endif
}
#endif /* CONFIG_NFILE_STREAMS */
diff --git a/nuttx/libc/stdio/Make.defs b/nuttx/libc/stdio/Make.defs
index 0670724da..32502f32c 100644
--- a/nuttx/libc/stdio/Make.defs
+++ b/nuttx/libc/stdio/Make.defs
@@ -37,7 +37,7 @@
# This first group of C files do not depend on having file descriptors or
# C streams.
-CSRCS += lib_fileno.c lib_printf.c lib_rawprintf.c lib_lowprintf.c \
+CSRCS += lib_fileno.c lib_printf.c lib_syslog.c lib_lowsyslog.c\
lib_sprintf.c lib_asprintf.c lib_snprintf.c lib_libsprintf.c \
lib_vsprintf.c lib_avsprintf.c lib_vsnprintf.c lib_libvsprintf.c \
lib_meminstream.c lib_memoutstream.c lib_lowinstream.c \
diff --git a/nuttx/libc/stdio/lib_fgets.c b/nuttx/libc/stdio/lib_fgets.c
index 35d024ebb..87eed285d 100644
--- a/nuttx/libc/stdio/lib_fgets.c
+++ b/nuttx/libc/stdio/lib_fgets.c
@@ -150,7 +150,7 @@ char *fgets(FAR char *buf, int buflen, FILE *stream)
if (ch == '\n')
#elif defined(CONFIG_EOL_IS_CR)
if (ch == '\r')
-#else /* elif CONFIG_EOL_IS_EITHER_CRLF */
+#else /* elif defined(CONFIG_EOL_IS_EITHER_CRLF) */
if (ch == '\n' || ch == '\r')
#endif
{
diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c
index 7ac3da7e0..22baed968 100644
--- a/nuttx/libc/stdio/lib_libflushall.c
+++ b/nuttx/libc/stdio/lib_libflushall.c
@@ -1,7 +1,7 @@
/****************************************************************************
* libc/stdio/lib_libflushall.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/libc/stdio/lib_libfread.c b/nuttx/libc/stdio/lib_libfread.c
index 3e851bf17..f8cf0f40a 100644
--- a/nuttx/libc/stdio/lib_libfread.c
+++ b/nuttx/libc/stdio/lib_libfread.c
@@ -1,7 +1,7 @@
/****************************************************************************
* libc/stdio/lib_libfread.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -88,7 +88,9 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream)
{
unsigned char *dest = (unsigned char*)ptr;
ssize_t bytes_read;
+#if CONFIG_STDIO_BUFFER_SIZE > 0
int ret;
+#endif
/* Make sure that reading from this stream is allowed */
diff --git a/nuttx/libc/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowsyslog.c
index f7d4ffe2f..bfe6a2cce 100644
--- a/nuttx/libc/stdio/lib_lowprintf.c
+++ b/nuttx/libc/stdio/lib_lowsyslog.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * libc/stdio/lib_lowprintf.c
+ * libc/stdio/lib_lowsyslog.c
*
* Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -38,8 +38,10 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <stdio.h>
#include <debug.h>
+
#include "lib_internal.h"
/* This interface can only be used from within the kernel */
@@ -83,12 +85,12 @@
****************************************************************************/
/****************************************************************************
- * Name: lib_lowvprintf
+ * Name: lowvsyslog
****************************************************************************/
#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_SYSLOG)
-int lib_lowvprintf(const char *fmt, va_list ap)
+int lowvsyslog(const char *fmt, va_list ap)
{
struct lib_outstream_s stream;
@@ -103,21 +105,21 @@ int lib_lowvprintf(const char *fmt, va_list ap)
}
/****************************************************************************
- * Name: lib_lowprintf
+ * Name: lowsyslog
****************************************************************************/
-int lib_lowprintf(const char *fmt, ...)
+int lowsyslog(const char *fmt, ...)
{
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, fmt);
- ret = lib_lowvprintf(fmt, ap);
+ ret = lowvsyslog(fmt, ap);
va_end(ap);
}
diff --git a/nuttx/libc/stdio/lib_printf.c b/nuttx/libc/stdio/lib_printf.c
index 0e90c7ca5..b035aa14f 100644
--- a/nuttx/libc/stdio/lib_printf.c
+++ b/nuttx/libc/stdio/lib_printf.c
@@ -93,9 +93,9 @@ int printf(const char *fmt, ...)
#if CONFIG_NFILE_STREAMS > 0
ret = vfprintf(stdout, fmt, ap);
#elif CONFIG_NFILE_DESCRIPTORS > 0
- ret = lib_rawvprintf(fmt, ap);
+ ret = vsyslog(fmt, ap);
#elif defined(CONFIG_ARCH_LOWPUTC)
- ret = lib_lowvprintf(fmt, ap);
+ ret = lowvsyslog(fmt, ap);
#else
# ifdef CONFIG_CPP_HAVE_WARNING
# warning "printf has no data sink"
diff --git a/nuttx/libc/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_syslog.c
index ddbb84f94..661c3b61e 100644
--- a/nuttx/libc/stdio/lib_rawprintf.c
+++ b/nuttx/libc/stdio/lib_syslog.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * libc/stdio/lib_rawprintf.c
+ * libc/stdio/lib_syslog.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -37,8 +37,11 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#include <stdio.h>
-#include <debug.h>
+#include <syslog.h>
+
#include "lib_internal.h"
/****************************************************************************
@@ -85,10 +88,10 @@
****************************************************************************/
/****************************************************************************
- * Name: lib_rawvprintf
+ * Name: vsyslog
****************************************************************************/
-int lib_rawvprintf(const char *fmt, va_list ap)
+int vsyslog(const char *fmt, va_list ap)
{
#if defined(CONFIG_SYSLOG)
@@ -129,21 +132,21 @@ int lib_rawvprintf(const char *fmt, va_list ap)
}
/****************************************************************************
- * Name: lib_rawprintf
+ * Name: syslog
****************************************************************************/
-int lib_rawprintf(const char *fmt, ...)
+int syslog(const char *fmt, ...)
{
va_list ap;
int ret;
-#ifdef CONFIG_DEBUG_ENABLE
+#ifdef CONFIG_SYSLOG_ENABLE
ret = 0;
- if (g_dbgenable)
+ if (g_syslogenable)
#endif
{
va_start(ap, fmt);
- ret = lib_rawvprintf(fmt, ap);
+ ret = vsyslog(fmt, ap);
va_end(ap);
}
diff --git a/nuttx/libc/stdio/lib_syslogstream.c b/nuttx/libc/stdio/lib_syslogstream.c
index 5529c5de8..e29c5ca3d 100644
--- a/nuttx/libc/stdio/lib_syslogstream.c
+++ b/nuttx/libc/stdio/lib_syslogstream.c
@@ -71,22 +71,23 @@ static void syslogstream_putc(FAR struct lib_outstream_s *this, int ch)
do
{
- /* Write the character to the supported logging device */
+ /* Write the character to the supported logging device. On failure,
+ * syslog_putc returns EOF with the errno value set;
+ */
ret = syslog_putc(ch);
- if (ret == OK)
+ if (ret != EOF)
{
this->nput++;
return;
}
- /* On failure syslog_putc will return a negated errno value. The
- * errno variable will not be set. The special value -EINTR means that
- * syslog_putc() was awakened by a signal. This is not a real error and
- * must be ignored in this context.
+ /* The special errno value -EINTR means that syslog_putc() was
+ * awakened by a signal. This is not a real error and must be
+ * ignored in this context.
*/
}
- while (ret == -EINTR);
+ while (errno == -EINTR);
}
/****************************************************************************
diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c
index 2e73bd73c..1838f541e 100644
--- a/nuttx/net/net_poll.c
+++ b/nuttx/net/net_poll.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/net_poll.c
*
- * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,11 +46,13 @@
#include <stdlib.h>
#include <poll.h>
#include <errno.h>
+#include <assert.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/arch.h>
#include <nuttx/net/uip/uip.h>
#include <nuttx/net/net.h>
-#include <nuttx/arch.h>
#include <uip/uip_internal.h>
@@ -75,6 +77,14 @@
/****************************************************************************
* Private Types
****************************************************************************/
+/* This is an allocated container that holds the poll-related information */
+
+struct net_poll_s
+{
+ FAR struct socket *psock; /* Needed to handle loss of connection */
+ struct pollfd *fds; /* Needed to handle poll events */
+ FAR struct uip_callback_s *cb; /* Needed to teardown the poll */
+};
/****************************************************************************
* Private Functions
@@ -101,16 +111,18 @@
****************************************************************************/
#ifdef HAVE_NETPOLL
-static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
+static uint16_t poll_interrupt(FAR struct uip_driver_s *dev, FAR void *conn,
FAR void *pvpriv, uint16_t flags)
{
- FAR struct pollfd *fds = (FAR struct pollfd *)pvpriv;
+ FAR struct net_poll_s *info = (FAR struct net_poll_s *)pvpriv;
nllvdbg("flags: %04x\n", flags);
+ DEBUGASSERT(!info || (info->psock && info->fds));
+
/* 'priv' might be null in some race conditions (?) */
- if (fds)
+ if (info)
{
pollevent_t eventset = 0;
@@ -118,24 +130,23 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
if ((flags & (UIP_NEWDATA|UIP_BACKLOG)) != 0)
{
- eventset |= POLLIN & fds->events;
+ eventset |= POLLIN & info->fds->events;
}
/* A poll is a sign that we are free to send data. */
if ((flags & UIP_POLL) != 0)
{
- eventset |= (POLLOUT & fds->events);
+ eventset |= (POLLOUT & info->fds->events);
}
- /* Check for a loss of connection events.
- *
- * REVISIT: Need to call net_lostconnection() here, but don't have
- * the psock instance. What should we do?
- */
+ /* Check for a loss of connection events. */
if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
{
+ /* Make the the connection has been lost */
+
+ net_lostconnection(info->psock, flags);
eventset |= (POLLERR | POLLHUP);
}
@@ -143,8 +154,8 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
if (eventset)
{
- fds->revents |= eventset;
- sem_post(fds->sem);
+ info->fds->revents |= eventset;
+ sem_post(info->fds->sem);
}
}
@@ -169,9 +180,11 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
****************************************************************************/
#ifdef HAVE_NETPOLL
-static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
+static inline int net_pollsetup(FAR struct socket *psock,
+ FAR struct pollfd *fds)
{
FAR struct uip_conn *conn = psock->s_conn;
+ FAR struct net_poll_s *info;
FAR struct uip_callback_s *cb;
uip_lock_t flags;
int ret;
@@ -185,6 +198,14 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
}
#endif
+ /* Allocate a container to hold the poll information */
+
+ info = (FAR struct net_poll_s *)kmalloc(sizeof(struct net_poll_s));
+ if (!info)
+ {
+ return -ENOMEM;
+ }
+
/* Some of the following must be atomic */
flags = uip_lock();
@@ -195,18 +216,29 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
if (!cb)
{
ret = -EBUSY;
- goto errout_with_irq;
+ goto errout_with_lock;
}
- /* Initialize the callback structure */
+ /* Initialize the poll info container */
+
+ info->psock = psock;
+ info->fds = fds;
+ info->cb = cb;
+
+ /* Initialize the callback structure. Save the reference to the info
+ * structure as callback private data so that it will be available during
+ * callback processing.
+ */
cb->flags = (UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT);
- cb->priv = (FAR void *)fds;
+ cb->priv = (FAR void *)info;
cb->event = poll_interrupt;
- /* Save the nps reference in the poll structure for use at teardown as well */
+ /* Save the reference in the poll info structure as fds private as well
+ * for use durring poll teardown as well.
+ */
- fds->priv = (FAR void *)cb;
+ fds->priv = (FAR void *)info;
#ifdef CONFIG_NET_TCPBACKLOG
/* Check for read data or backlogged connection availability now */
@@ -240,7 +272,8 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
uip_unlock(flags);
return OK;
-errout_with_irq:
+errout_with_lock:
+ kfree(info);
uip_unlock(flags);
return ret;
}
@@ -261,10 +294,11 @@ errout_with_irq:
****************************************************************************/
#ifdef HAVE_NETPOLL
-static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
+static inline int net_pollteardown(FAR struct socket *psock,
+ FAR struct pollfd *fds)
{
FAR struct uip_conn *conn = psock->s_conn;
- FAR struct uip_callback_s *cb;
+ FAR struct net_poll_s *info;
uip_lock_t flags;
/* Sanity check */
@@ -278,18 +312,23 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
/* Recover the socket descriptor poll state info from the poll structure */
- cb = (FAR struct uip_callback_s *)fds->priv;
- if (cb)
+ info = (FAR struct net_poll_s *)fds->priv;
+ DEBUGASSERT(info && info->fds && info->cb);
+ if (info)
{
/* Release the callback */
flags = uip_lock();
- uip_tcpcallbackfree(conn, cb);
+ uip_tcpcallbackfree(conn, info->cb);
uip_unlock(flags);
/* Release the poll/select data slot */
- fds->priv = NULL;
+ info->fds->priv = NULL;
+
+ /* Then free the poll info container */
+
+ kfree(info);
}
return OK;
@@ -308,7 +347,7 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
* to this function.
*
* Input Parameters:
- * fd - The socket descriptor of interest
+ * psock - An instance of the internal socket structure.
* fds - The structure describing the events to be monitored, OR NULL if
* this is a request to stop monitoring events.
* setup - true: Setup up the poll; false: Teardown the poll
@@ -318,33 +357,17 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
*
****************************************************************************/
-#ifndef CONFIG_DISABLE_POLL
-int net_poll(int sockfd, struct pollfd *fds, bool setup)
+#if !defined(CONFIG_DISABLE_POLL) && defined(HAVE_NETPOLL)
+int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup)
{
-#ifndef HAVE_NETPOLL
- return -ENOSYS;
-#else
- FAR struct socket *psock;
int ret;
- /* Get the underlying socket structure and verify that the sockfd
- * corresponds to valid, allocated socket
- */
-
- psock = sockfd_socket(sockfd);
- if (!psock || psock->s_crefs <= 0)
- {
- ret = -EBADF;
- goto errout;
- }
-
#ifdef CONFIG_NET_UDP
/* poll() not supported for UDP */
if (psock->s_type != SOCK_STREAM)
{
- ret = -ENOSYS;
- goto errout;
+ return -ENOSYS;
}
#endif
@@ -363,8 +386,49 @@ int net_poll(int sockfd, struct pollfd *fds, bool setup)
ret = net_pollteardown(psock, fds);
}
-errout:
return ret;
+}
+#endif
+
+/****************************************************************************
+ * Function: net_poll
+ *
+ * Description:
+ * The standard poll() operation redirects operations on socket descriptors
+ * to this function.
+ *
+ * Input Parameters:
+ * fd - The socket descriptor of interest
+ * fds - The structure describing the events to be monitored, OR NULL if
+ * this is a request to stop monitoring events.
+ * setup - true: Setup up the poll; false: Teardown the poll
+ *
+ * Returned Value:
+ * 0: Success; Negated errno on failure
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_POLL
+int net_poll(int sockfd, struct pollfd *fds, bool setup)
+{
+#ifndef HAVE_NETPOLL
+ return -ENOSYS;
+#else
+ FAR struct socket *psock;
+
+ /* Get the underlying socket structure and verify that the sockfd
+ * corresponds to valid, allocated socket
+ */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock || psock->s_crefs <= 0)
+ {
+ return -EBADF;
+ }
+
+ /* Then let psock_poll() do the heavy lifting */
+
+ return psock_poll(psock, fds, setup);
#endif /* HAVE_NETPOLL */
}
#endif /* !CONFIG_DISABLE_POLL */
diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c
index 81e48c121..ddb54c98c 100644
--- a/nuttx/net/net_sockets.c
+++ b/nuttx/net/net_sockets.c
@@ -116,99 +116,37 @@ void net_initialize(void)
#if CONFIG_NSOCKET_DESCRIPTORS > 0
-/* Allocate a list of files for a new task */
+/* Initialize a list of sockets for a new task */
-FAR struct socketlist *net_alloclist(void)
+void net_initlist(FAR struct socketlist *list)
{
- FAR struct socketlist *list;
- list = (FAR struct socketlist*)kzalloc(sizeof(struct socketlist));
- if (list)
- {
- /* Start with a reference count of one */
-
- list->sl_crefs = 1;
-
- /* Initialize the list access mutex */
+ /* Initialize the list access mutex */
- (void)sem_init(&list->sl_sem, 0, 1);
- }
- return list;
+ (void)sem_init(&list->sl_sem, 0, 1);
}
-/* Increase the reference count on a file list */
+/* Release release resources held by the socket list */
-int net_addreflist(FAR struct socketlist *list)
+void net_releaselist(FAR struct socketlist *list)
{
- if (list)
- {
- /* Increment the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- register uip_lock_t flags = uip_lock();
- list->sl_crefs++;
- uip_unlock(flags);
- }
- return OK;
-}
+ int ndx;
-/* Release a reference to the file list */
+ DEBUGASSERT(list);
-int net_releaselist(FAR struct socketlist *list)
-{
- int crefs;
- int ndx;
+ /* Close each open socket in the list. */
- if (list)
+ for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++)
{
- /* Decrement the reference count on the list.
- * NOTE: that we disable interrupts to do this
- * (vs. taking the list semaphore). We do this
- * because file cleanup operations often must be
- * done from the IDLE task which cannot wait
- * on semaphores.
- */
-
- uip_lock_t flags = uip_lock();
- crefs = --(list->sl_crefs);
- uip_unlock(flags);
-
- /* If the count decrements to zero, then there is no reference
- * to the structure and it should be deallocated. Since there
- * are references, it would be an error if any task still held
- * a reference to the list's semaphore.
- */
-
- if (crefs <= 0)
- {
- /* Close each open socket in the list
- * REVISIT: psock_close() will attempt to use semaphores.
- * If we actually are in the IDLE thread, then could this cause
- * problems? Probably not, if the task has exited and crefs is
- * zero, then there probably could not be a contender for the
- * semaphore.
- */
-
- for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++)
- {
- FAR struct socket *psock = &list->sl_sockets[ndx];
- if (psock->s_crefs > 0)
- {
- (void)psock_close(psock);
- }
- }
-
- /* Destroy the semaphore and release the filelist */
-
- (void)sem_destroy(&list->sl_sem);
- sched_free(list);
- }
+ FAR struct socket *psock = &list->sl_sockets[ndx];
+ if (psock->s_crefs > 0)
+ {
+ (void)psock_close(psock);
+ }
}
- return OK;
+
+ /* Destroy the semaphore */
+
+ (void)sem_destroy(&list->sl_sem);
}
int sockfd_allocate(int minsd)
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 79dfef4ec..b26a0e5bb 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -448,7 +448,7 @@ end_wait:
* equivalent to sendto(sockfd,buf,len,flags,NULL,0).
*
* Parameters:
- * psock And instance of the internal socket structure.
+ * psock An instance of the internal socket structure.
* buf Data to send
* len Length of data to send
* flags Send flags
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index fe9a88085..097dd1993 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -124,6 +124,13 @@ config PREALLOC_CHILDSTATUS
sa.sa_flags = SA_NOCLDWAIT;
int ret = sigaction(SIGCHLD, &sa, NULL);
+config DEBUG_CHILDSTATUS
+ bool "Enable Child Status Debug Output"
+ default n
+ depends on SCHED_CHILD_STATUS && DEBUG
+ ---help---
+ Very detailed... I am sure that you do not want this.
+
config JULIAN_TIME
bool "Enables Julian time conversions"
default n
@@ -289,6 +296,16 @@ config SCHED_WAITPID
compliant) and will enable the waitid() and wait() interfaces as
well.
+config SCHED_STARTHOOK
+ bool "Enable startup hook"
+ default n
+ ---help---
+ Enable a non-standard, internal OS API call task_starthook().
+ task_starthook() registers a function that will be called on task
+ startup before that actual task entry point is called. The
+ starthook is useful, for example, for setting up automatic
+ configuration of C++ constructors.
+
config SCHED_ATEXIT
bool "Enable atexit() API"
default n
@@ -379,21 +396,11 @@ config DISABLE_MQUEUE
depends on DISABLE_OS_API
default n
-config DISABLE_MOUNTPOINT
- bool "Disable support for mount points"
- depends on DISABLE_OS_API
- default n
-
config DISABLE_ENVIRON
bool "Disable environment variable support"
depends on DISABLE_OS_API
default n
-config DISABLE_POLL
- bool "Disable driver poll interfaces"
- depends on DISABLE_OS_API
- default n
-
if !DISABLE_SIGNALS
comment "Signal Numbers"
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 1ad244450..961560176 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -39,9 +39,7 @@ ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c
-MISC_SRCS += sched_garbage.c sched_setupstreams.c sched_getfiles.c sched_getsockets.c
-MISC_SRCS += sched_getstreams.c sched_setupidlefiles.c sched_setuptaskfiles.c
-MISC_SRCS += sched_setuppthreadfiles.c sched_releasefiles.c
+MISC_SRCS += sched_garbage.c sched_getfiles.c sched_getsockets.c sched_getstreams.c
TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c
TSK_SRCS += task_start.c task_delete.c task_deletecurrent.c task_exithook.c
@@ -56,6 +54,10 @@ TSK_SRCS += task_posixspawn.c
endif
endif
+ifeq ($(CONFIG_SCHED_STARTHOOK),y)
+TSK_SRCS += task_starthook.c
+endif
+
SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c
SCHED_SRCS += sched_setscheduler.c sched_getscheduler.c
SCHED_SRCS += sched_yield.c sched_rrgetinterval.c sched_foreach.c
@@ -73,21 +75,28 @@ ifeq ($(CONFIG_PRIORITY_INHERITANCE),y)
SCHED_SRCS += sched_reprioritize.c
endif
+ifeq ($(CONFIG_SCHED_WAITPID),y)
+SCHED_SRCS += sched_waitpid.c
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
-SCHED_SRCS += task_reparent.c
-ifeq ($(CONFIG_SCHED_CHILD_STATUS),y)
-SCHED_SRCS += task_childstatus.c
+SCHED_SRCS += sched_waitid.c sched_wait.c
endif
endif
-ifeq ($(CONFIG_SCHED_WAITPID),y)
-SCHED_SRCS += sched_waitpid.c
+GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c
+GRP_SRCS += group_setupstreams.c group_setupidlefiles.c group_setuptaskfiles.c
+
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
-SCHED_SRCS += sched_waitid.c sched_wait.c
+GRP_SRCS += task_reparent.c
+ifeq ($(CONFIG_SCHED_CHILD_STATUS),y)
+GRP_SRCS += group_childstatus.c
endif
endif
-ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c
+ifneq ($(CONFIG_DISABLE_SIGNALS),y)
+GRP_SRCS += group_signal.c
+endif
+
+ENV_SRCS = env_getenvironptr.c env_dup.c env_release.c
ENV_SRCS += env_findvar.c env_removevar.c
ENV_SRCS += env_clearenv.c env_getenv.c env_putenv.c env_setenv.c env_unsetenv.c
@@ -169,8 +178,9 @@ IRQ_SRCS = irq_initialize.c irq_attach.c irq_dispatch.c irq_unexpectedisr.c
KMM_SRCS = kmm_initialize.c kmm_addregion.c kmm_semaphore.c
KMM_SRCS = kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c
-CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(SCHED_SRCS) $(WDOG_SRCS) $(TIME_SRCS) \
- $(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS) $(IRQ_SRCS)
+CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(GRP_SRCS) $(SCHED_SRCS) $(WDOG_SRCS)
+CSRCS += $(TIME_SRCS) $(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS)
+CSRCS += $(IRQ_SRCS)
ifneq ($(CONFIG_DISABLE_CLOCK),y)
CSRCS += $(CLOCK_SRCS)
diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c
index 75890f3bc..062fd60ed 100644
--- a/nuttx/sched/env_clearenv.c
+++ b/nuttx/sched/env_clearenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_clearenv.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -74,7 +74,11 @@
int clearenv(void)
{
- return env_release((FAR _TCB*)g_readytorun.head);
+ FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
+ DEBUGASSERT(tcb->group);
+
+ env_release(tcb->group);
+ return OK;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c
index 033348411..3b653b010 100644
--- a/nuttx/sched/env_dup.c
+++ b/nuttx/sched/env_dup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_dup.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,8 +68,8 @@
* exact duplicate of the parent task's environment.
*
* Parameters:
- * ptcb The tcb to receive the newly allocated copy of the parspecifiedent
- * TCB's environment structure with reference count equal to one
+ * group The child task group to receive the newly allocated copy of the
+ * parent task groups environment structure.
*
* Return Value:
* zero on success
@@ -79,50 +79,42 @@
*
****************************************************************************/
-int env_dup(FAR _TCB *ptcb)
+int env_dup(FAR struct task_group_s *group)
{
+ FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head;
+ FAR char *envp = NULL;
+ size_t envlen;
int ret = OK;
- if (!ptcb )
- {
- ret = -EINVAL;
- }
- else
- {
- FAR _TCB *parent = (FAR _TCB*)g_readytorun.head;
- environ_t *envp = NULL;
- /* Pre-emption must be disabled throughout the following because the
- * environment may be shared.
- */
+ DEBUGASSERT(group && ptcb && ptcb->group);
- sched_lock();
+ /* Pre-emption must be disabled throughout the following because the
+ * environment may be shared.
+ */
- /* Does the parent task have an environment? */
+ sched_lock();
- if (parent->envp)
- {
- /* Yes..The parent task has an environment, duplicate it */
-
- size_t envlen = parent->envp->ev_alloc;
- envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen ));
- if (!envp)
- {
- ret = -ENOMEM;
- }
- else
- {
- envp->ev_crefs = 1;
- envp->ev_alloc = envlen;
- memcpy( envp->ev_env, parent->envp->ev_env, envlen );
- }
- }
+ /* Does the parent task have an environment? */
- /* Save the cloned environment in the new TCB */
+ if (ptcb->group && ptcb->group->tg_envp)
+ {
+ /* Yes..The parent task has an environment, duplicate it */
- ptcb->envp = envp;
- sched_unlock();
- }
+ envlen = ptcb->group->tg_envsize;
+ envp = (FAR char *)kmalloc(envlen);
+ if (!envp)
+ {
+ ret = -ENOMEM;
+ }
+ else
+ {
+ group->tg_envsize = envlen;
+ group->tg_envp = envp;
+ memcpy(envp, ptcb->group->tg_envp, envlen);
+ }
+ }
+ sched_unlock();
return ret;
}
diff --git a/nuttx/sched/env_findvar.c b/nuttx/sched/env_findvar.c
index a8e94180c..a744c6c3a 100644
--- a/nuttx/sched/env_findvar.c
+++ b/nuttx/sched/env_findvar.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_findvar.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -85,7 +85,7 @@ static bool env_cmpname(const char *pszname, const char *peqname)
* specified name.
*
* Parameters:
- * envp The environment structre to be searched.
+ * group The task group containging environment array to be searched.
* pname The variable name to find
*
* Return Value:
@@ -97,32 +97,25 @@ static bool env_cmpname(const char *pszname, const char *peqname)
*
****************************************************************************/
-FAR char *env_findvar(environ_t *envp, const char *pname)
+FAR char *env_findvar(FAR struct task_group_s *group, const char *pname)
{
- char *ret = NULL;
+ char *ptr;
+ char *end;
/* Verify input parameters */
- if (envp && pname)
- {
- char *ptr;
- char *end = &envp->ev_env[envp->ev_alloc];
-
- /* Search for a name=value string with matching name */
+ DEBUGASSERT(group && pname);
- for (ptr = envp->ev_env;
- ptr < end && !env_cmpname( pname, ptr);
- ptr += (strlen(ptr) + 1));
+ /* Search for a name=value string with matching name */
- /* Check for success */
+ end = &group->tg_envp[group->tg_envsize];
+ for (ptr = group->tg_envp;
+ ptr < end && !env_cmpname(pname, ptr);
+ ptr += (strlen(ptr) + 1));
- if (ptr < end)
- {
- ret = ptr;
- }
- }
+ /* Check for success */
- return ret;
+ return (ptr < end) ? ptr : NULL;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/env_getenv.c b/nuttx/sched/env_getenv.c
index ee8d798b1..4709bc380 100644
--- a/nuttx/sched/env_getenv.c
+++ b/nuttx/sched/env_getenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* env_getenv.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,10 +77,10 @@
FAR char *getenv(const char *name)
{
- FAR _TCB *rtcb;
- FAR environ_t *envp;
- FAR char *pvar;
- FAR char *pvalue = NULL;
+ FAR _TCB *rtcb;
+ FAR struct task_group_s *group;
+ FAR char *pvar;
+ FAR char *pvalue = NULL;
int ret = OK;
/* Verify that a string was passed */
@@ -95,11 +95,11 @@ FAR char *getenv(const char *name)
sched_lock();
rtcb = (FAR _TCB*)g_readytorun.head;
- envp = rtcb->envp;
+ group = rtcb->group;
/* Check if the variable exists */
- if ( !envp || (pvar = env_findvar(envp, name)) == NULL)
+ if ( !group || (pvar = env_findvar(group, name)) == NULL)
{
ret = ENOENT;
goto errout_with_lock;
diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h
index 5370da059..e02bf289d 100644
--- a/nuttx/sched/env_internal.h
+++ b/nuttx/sched/env_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_internal.h
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,10 +49,9 @@
****************************************************************************/
#ifdef CONFIG_DISABLE_ENVIRON
-# define env_dup(ptcb) (0)
-# define env_share(ptcb) (0)
-# define env_release(ptcb) (0)
-#endif
+# define env_dup(group) (0)
+# define env_release(group) (0)
+#else
/****************************************************************************
* Public Type Declarations
@@ -62,34 +61,33 @@
* Public Variables
****************************************************************************/
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
-#ifndef CONFIG_DISABLE_ENVIRON
-/* functions used by the task/pthread creation and destruction logic */
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
-EXTERN int env_dup(FAR _TCB *ptcb);
-EXTERN int env_share(FAR _TCB *ptcb);
-EXTERN int env_release(FAR _TCB *ptcb);
+/* Functions used by the task/pthread creation and destruction logic */
-/* functions used internally by the environment handling logic */
+int env_dup(FAR struct task_group_s *group);
+void env_release(FAR struct task_group_s *group);
-EXTERN FAR char *env_findvar(environ_t *envp, const char *pname);
-EXTERN int env_removevar(environ_t *envp, char *pvar);
-#endif
+/* Functions used internally by the environment handling logic */
+
+FAR char *env_findvar(FAR struct task_group_s *group, FAR const char *pname);
+int env_removevar(FAR struct task_group_s *group, FAR char *pvar);
#undef EXTERN
#ifdef __cplusplus
}
#endif
+#endif /* !CONFIG_DISABLE_ENVIRON */
#endif /* __SCHED_ENV_INTERNAL_H */
diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c
index 8bc8d2205..aebb1f7e8 100644
--- a/nuttx/sched/env_release.c
+++ b/nuttx/sched/env_release.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/env_clearenv.c
+ * sched/env_release.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,65 +58,42 @@
* Name: env_release
*
* Description:
- * The env_release() function clears the environment of all name-value
- * pairs and sets the value of the external variable environ to NULL.
+ * env_release() is called only from group_leave() when the last member of
+ * a task group exits. The env_release() function clears the environment
+ * of all name-value pairs and sets the value of the external variable
+ * environ to NULL.
*
* Parameters:
- * ptcb Identifies the TCB containing the environment structure
+ * group Identifies the task group containing the environment structure
+ * to be released.
*
* Return Value:
- * zero on success
+ * None
*
* Assumptions:
* Not called from an interrupt handler
*
****************************************************************************/
-int env_release(FAR _TCB *ptcb)
+void env_release(FAR struct task_group_s *group)
{
- int ret = OK;
+ DEBUGASSERT(group);
- if (!ptcb)
- {
- ret = -EINVAL;
- }
- else
- {
- FAR environ_t *envp;
-
- /* Examine the environ data in the TCB. Preemption is disabled because the
- * the environment could be shared among threads.
- */
-
- sched_lock();
- envp = ptcb->envp;
- if (ptcb->envp)
- {
- /* Check the reference count on the environment structure */
-
- if (envp->ev_crefs <= 1)
- {
- /* Decrementing the reference count will destroy the environment */
+ /* Free any allocate environment strings */
- sched_free(envp);
- }
- else
- {
- /* The environment will persist after decrementing the reference
- * count */
-
- envp->ev_crefs--;
- }
-
- /* In any case, the environment is no longer accessible on this thread */
-
- ptcb->envp = NULL;
- }
+ if (group->tg_envp)
+ {
+ /* Free the environment */
- sched_unlock();
+ sched_free(group->tg_envp);
}
- return ret;
+ /* In any event, make sure that all environment-related varialbles in the
+ * task group structure are reset to initial values.
+ */
+
+ group->tg_envsize = 0;
+ group->tg_envp = NULL;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/env_removevar.c b/nuttx/sched/env_removevar.c
index e96aa7a37..811e6079e 100644
--- a/nuttx/sched/env_removevar.c
+++ b/nuttx/sched/env_removevar.c
@@ -59,7 +59,7 @@
* Remove the referenced name=value pair from the environment
*
* Parameters:
- * envp The environment containing the name=value pair
+ * group The task group with the environment containing the name=value pair
* pvar A pointer to the name=value pair in the restroom
*
* Return Value:
@@ -72,42 +72,44 @@
*
****************************************************************************/
-int env_removevar(environ_t *envp, char *pvar)
+int env_removevar(FAR struct task_group_s *group, FAR char *pvar)
{
+ FAR char *end; /* Pointer to the end+1 of the environment */
+ int alloc; /* Size of the allocated environment */
int ret = ERROR;
- if (envp && pvar)
- {
- /* Verify that the pointer lies within the environment region */
- int alloc = envp->ev_alloc; /* Size of the allocated environment */
- char *end = &envp->ev_env[alloc]; /* Pointer to the end+1 of the environment */
+ DEBUGASSERT(group && pvar);
- if (pvar >= envp->ev_env && pvar < end)
- {
- /* Set up for the removal */
+ /* Verify that the pointer lies within the environment region */
- int len = strlen(pvar) + 1; /* Length of name=value string to remove */
- char *src = &pvar[len]; /* Address of name=value string after */
- char *dest = pvar; /* Location to move the next string */
- int count = end - src; /* Number of bytes to move (might be zero) */
+ alloc = group->tg_envsize; /* Size of the allocated environment */
+ end = &group->tg_envp[alloc]; /* Pointer to the end+1 of the environment */
- /* Move all of the environment strings after the removed one 'down.'
- * this is inefficient, but robably not high duty.
- */
+ if (pvar >= group->tg_envp && pvar < end)
+ {
+ /* Set up for the removal */
- while (count-- > 0)
- {
- *dest++ = *src++;
- }
+ int len = strlen(pvar) + 1; /* Length of name=value string to remove */
+ char *src = &pvar[len]; /* Address of name=value string after */
+ char *dest = pvar; /* Location to move the next string */
+ int count = end - src; /* Number of bytes to move (might be zero) */
- /* Then set to the new allocation size. The caller is expected to
- * call realloc at some point but we don't do that here because the
- * caller may add more stuff to the environment.
- */
+ /* Move all of the environment strings after the removed one 'down.'
+ * this is inefficient, but robably not high duty.
+ */
- envp->ev_alloc -= len;
- ret = OK;
+ while (count-- > 0)
+ {
+ *dest++ = *src++;
}
+
+ /* Then set to the new allocation size. The caller is expected to
+ * call realloc at some point but we don't do that here because the
+ * caller may add more stuff to the environment.
+ */
+
+ group->tg_envsize -= len;
+ ret = OK;
}
return ret;
diff --git a/nuttx/sched/env_setenv.c b/nuttx/sched/env_setenv.c
index c186241ef..cfde71604 100644
--- a/nuttx/sched/env_setenv.c
+++ b/nuttx/sched/env_setenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_setenv.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -83,12 +83,14 @@
*
****************************************************************************/
-int setenv(const char *name, const char *value, int overwrite)
+int setenv(FAR const char *name, FAR const char *value, int overwrite)
{
- FAR _TCB *rtcb;
- FAR environ_t *envp;
- FAR char *pvar;
- int varlen;
+ FAR _TCB *rtcb;
+ FAR struct task_group_s *group;
+ FAR char *pvar;
+ FAR char *newenvp;
+ int newsize;
+ int varlen;
int ret = OK;
/* Verify input parameter */
@@ -122,14 +124,15 @@ int setenv(const char *name, const char *value, int overwrite)
/* Get a reference to the thread-private environ in the TCB.*/
sched_lock();
- rtcb = (FAR _TCB*)g_readytorun.head;
- envp = rtcb->envp;
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ group = rtcb->group;
+ DEBUGASSERT(group);
- /* Check if the variable alreay exists */
+ /* Check if the variable already exists */
- if ( envp && (pvar = env_findvar(envp, name)) != NULL)
+ if (group->tg_envp && (pvar = env_findvar(group, name)) != NULL)
{
- /* It does! Do we have permission to overwrite the existing value? */
+ /* It does! Do we have permission to overwrite the existing value? */
if (!overwrite)
{
@@ -144,7 +147,7 @@ int setenv(const char *name, const char *value, int overwrite)
* the environment buffer; this will happen below.
*/
- (void)env_removevar(envp, pvar);
+ (void)env_removevar(group, pvar);
}
/* Get the size of the new name=value string. The +2 is for the '=' and for
@@ -155,43 +158,39 @@ int setenv(const char *name, const char *value, int overwrite)
/* Then allocate or reallocate the environment buffer */
- if (envp)
+ if (group->tg_envp)
{
- int alloc = envp->ev_alloc;
- environ_t *tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc + varlen));
- if (!tmp)
+ newsize = group->tg_envsize + varlen;
+ newenvp = (FAR char *)krealloc(group->tg_envp, newsize);
+ if (!newenvp)
{
ret = ENOMEM;
goto errout_with_lock;
}
- envp = tmp;
- envp->ev_alloc = alloc + varlen;
- pvar = &envp->ev_env[alloc];
+ pvar = &newenvp[group->tg_envsize];
}
else
{
- envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(varlen));
- if (!envp)
+ newsize = varlen;
+ newenvp = (FAR char *)kmalloc(varlen);
+ if (!newenvp)
{
ret = ENOMEM;
goto errout_with_lock;
}
- envp->ev_crefs = 1;
- envp->ev_alloc = varlen;
- pvar = envp->ev_env;
+ pvar = newenvp;
}
- /* Now, put the new name=value string into the environment buffer */
+ /* Save the new buffer and size */
- sprintf(pvar, "%s=%s", name, value);
+ group->tg_envp = newenvp;
+ group->tg_envsize = newsize;
- /* Save the new environment pointer (it might have changed due to allocation or
- * reallocation.
- */
+ /* Now, put the new name=value string into the environment buffer */
- rtcb->envp = envp;
+ sprintf(pvar, "%s=%s", name, value);
sched_unlock();
return OK;
diff --git a/nuttx/sched/env_unsetenv.c b/nuttx/sched/env_unsetenv.c
index 52469fac9..8206a4ece 100644
--- a/nuttx/sched/env_unsetenv.c
+++ b/nuttx/sched/env_unsetenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_unsetenv.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -75,61 +75,47 @@
*
****************************************************************************/
-int unsetenv(const char *name)
+int unsetenv(FAR const char *name)
{
- FAR _TCB *rtcb;
- FAR environ_t *envp;
- FAR char *pvar;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->group;
+ FAR char *pvar;
+ FAR char *newenvp;
+ int newsize;
int ret = OK;
- /* Verify input parameter */
-
- if (!name)
- {
- ret = EINVAL;
- goto errout;
- }
-
- /* Get a reference to the thread-private environ in the TCB.*/
-
- sched_lock();
- rtcb = (FAR _TCB*)g_readytorun.head;
- envp = rtcb->envp;
+ DEBUGASSERT(name && group);
/* Check if the variable exists */
- if ( envp && (pvar = env_findvar(envp, name)) != NULL)
+ sched_lock();
+ if (group && (pvar = env_findvar(group, name)) != NULL)
{
- int alloc;
- environ_t *tmp;
-
/* It does! Remove the name=value pair from the environment. */
- (void)env_removevar(envp, pvar);
+ (void)env_removevar(group, pvar);
/* Reallocate the new environment buffer */
- alloc = envp->ev_alloc;
- tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc));
- if (!tmp)
+ newsize = group->tg_envsize;
+ newenvp = (FAR char *)krealloc(group->tg_envp, newsize);
+ if (!newenvp)
{
- ret = ENOMEM;
- goto errout_with_lock;
+ set_errno(ENOMEM);
+ ret = ERROR;
}
+ else
+ {
+ /* Save the new environment pointer (it might have changed due to
+ * reallocation.
+ */
- /* Save the new environment pointer (it might have changed due to reallocation. */
-
- rtcb->envp = tmp;
+ group->tg_envp = newenvp;
+ }
}
sched_unlock();
- return OK;
-
-errout_with_lock:
- sched_unlock();
-errout:
- errno = ret;
- return ERROR;
+ return ret;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/group_childstatus.c
index 0f6d36c29..ef42b6c34 100644
--- a/nuttx/sched/task_childstatus.c
+++ b/nuttx/sched/group_childstatus.c
@@ -1,5 +1,5 @@
/*****************************************************************************
- * sched/task_childstatus.c
+ * sched/group_childstatus.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -44,6 +44,7 @@
#include <debug.h>
#include "os_internal.h"
+#include "group_internal.h"
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
@@ -91,13 +92,13 @@ static struct child_pool_s g_child_pool;
*****************************************************************************/
/*****************************************************************************
- * Name: task_dumpchildren
+ * Name: group_dumpchildren
*
* Description:
* Dump all of the children when the part TCB list is modified.
*
* Parameters:
- * tcb - The parent TCB.
+ * group - The task group containing the child status.
*
* Return Value:
* None.
@@ -108,20 +109,21 @@ static struct child_pool_s g_child_pool;
*****************************************************************************/
#ifdef CONFIG_DEBUG_CHILDSTATUS
-static void task_dumpchildren(FAR _TCB *tcb, FAR const char *msg)
+static void group_dumpchildren(FAR struct task_group_s *group,
+ FAR const char *msg)
{
FAR struct child_status_s *child;
int i;
- dbg("Parent TCB=%p: %s\n", tcb, msg);
- for (i = 0, child = tcb->children; child; i++, child = child->flink)
+ dbg("Task group=%p: %s\n", group, msg);
+ for (i = 0, child = group->tg_children; child; i++, child = child->flink)
{
dbg(" %d. ch_flags=%02x ch_pid=%d ch_status=%d\n",
i, child->ch_flags, child->ch_pid, child->ch_status);
}
}
#else
-# task_dumpchildren(t,m)
+# define group_dumpchildren(t,m)
#endif
/*****************************************************************************
@@ -165,7 +167,7 @@ void task_initialize(void)
}
/*****************************************************************************
- * Name: task_allocchild
+ * Name: group_allocchild
*
* Description:
* Allocate a child status structure by removing the next entry from a
@@ -184,7 +186,7 @@ void task_initialize(void)
*
*****************************************************************************/
-FAR struct child_status_s *task_allocchild(void)
+FAR struct child_status_s *group_allocchild(void)
{
FAR struct child_status_s *ret;
@@ -201,7 +203,7 @@ FAR struct child_status_s *task_allocchild(void)
}
/*****************************************************************************
- * Name: task_freechild
+ * Name: group_freechild
*
* Description:
* Release a child status structure by returning it to a free list.
@@ -218,7 +220,7 @@ FAR struct child_status_s *task_allocchild(void)
*
*****************************************************************************/
-void task_freechild(FAR struct child_status_s *child)
+void group_freechild(FAR struct child_status_s *child)
{
/* Return the child status structure to the free list */
@@ -230,13 +232,13 @@ void task_freechild(FAR struct child_status_s *child)
}
/*****************************************************************************
- * Name: task_addchild
+ * Name: group_addchild
*
* Description:
* Add a child status structure in the given TCB.
*
* Parameters:
- * tcb - The TCB of the parent task to containing the child status.
+ * group - The task group for the child status.
* child - The structure to be added
*
* Return Value:
@@ -248,26 +250,27 @@ void task_freechild(FAR struct child_status_s *child)
*
*****************************************************************************/
-void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child)
+void group_addchild(FAR struct task_group_s *group,
+ FAR struct child_status_s *child)
{
/* Add the entry into the TCB list of children */
- child->flink = tcb->children;
- tcb->children = child;
+ child->flink = group->tg_children;
+ group->tg_children = child;
- task_dumpchildren(tcb, "task_addchild");
+ group_dumpchildren(group, "group_addchild");
}
/*****************************************************************************
- * Name: task_findchild
+ * Name: group_findchild
*
* Description:
- * Find a child status structure in the given TCB. A reference to the
- * child structure is returned, but the child remains the the TCB's list
- * of children.
+ * Find a child status structure in the given task group. A reference to
+ * the child structure is returned, but the child remains the the group's
+ * list of children.
*
* Parameters:
- * tcb - The TCB of the parent task to containing the child status.
+ * group - The ID of the parent task group to containing the child status.
* pid - The ID of the child to find.
*
* Return Value:
@@ -280,13 +283,16 @@ void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child)
*
*****************************************************************************/
-FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
+FAR struct child_status_s *group_findchild(FAR struct task_group_s *group,
+ pid_t pid)
{
FAR struct child_status_s *child;
+ DEBUGASSERT(group);
+
/* Find the status structure with the matching PID */
- for (child = tcb->children; child; child = child->flink)
+ for (child = group->tg_children; child; child = child->flink)
{
if (child->ch_pid == pid)
{
@@ -298,15 +304,51 @@ FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
}
/*****************************************************************************
- * Name: task_removechild
+ * Name: group_exitchild
*
* Description:
- * Remove one child structure from the TCB. The child is removed, but is
- * not yet freed. task_freechild must be called in order to free the child
- * status structure.
+ * Search for any child that has exitted.
*
* Parameters:
* tcb - The TCB of the parent task to containing the child status.
+ *
+ * Return Value:
+ * On success, a non-NULL pointer to a child status structure for the
+ * exited child. NULL is returned if not child has exited.
+ *
+ * Assumptions:
+ * Called during SIGCHLD processing in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group)
+{
+ FAR struct child_status_s *child;
+
+ /* Find the status structure of any child task that has exitted. */
+
+ for (child = group->tg_children; child; child = child->flink)
+ {
+ if ((child->ch_flags & CHILD_FLAG_EXITED) != 0)
+ {
+ return child;
+ }
+ }
+
+ return NULL;
+}
+
+/*****************************************************************************
+ * Name: group_removechild
+ *
+ * Description:
+ * Remove one child structure from a task group. The child is removed, but
+ * is not yet freed. group_freechild must be called in order to free the
+ * child status structure.
+ *
+ * Parameters:
+ * group - The task group containing the child status.
* pid - The ID of the child to find.
*
* Return Value:
@@ -319,14 +361,17 @@ FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
*
*****************************************************************************/
-FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
+FAR struct child_status_s *group_removechild(FAR struct task_group_s *group,
+ pid_t pid)
{
FAR struct child_status_s *curr;
FAR struct child_status_s *prev;
- /* Find the status structure with the matching PID */
+ DEBUGASSERT(group);
- for (prev = NULL, curr = tcb->children;
+ /* Find the status structure with the matching PID */
+
+ for (prev = NULL, curr = group->tg_children;
curr;
prev = curr, curr = curr->flink)
{
@@ -336,7 +381,7 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
}
}
- /* Did we find it? If so, remove it from the TCB. */
+ /* Did we find it? If so, remove it from the group. */
if (curr)
{
@@ -348,24 +393,24 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
}
else
{
- tcb->children = curr->flink;
+ group->tg_children = curr->flink;
}
curr->flink = NULL;
- task_dumpchildren(tcb, "task_removechild");
+ group_dumpchildren(group, "group_removechild");
}
return curr;
}
/*****************************************************************************
- * Name: task_removechildren
+ * Name: group_removechildren
*
* Description:
- * Remove and free all child structure from the TCB.
+ * Remove and free all child structure from the task group.
*
* Parameters:
- * tcb - The TCB of the parent task to containing the child status.
+ * group - The task group containing the child status.
*
* Return Value:
* None.
@@ -376,21 +421,21 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
*
*****************************************************************************/
-void task_removechildren(FAR _TCB *tcb)
+void group_removechildren(FAR struct task_group_s *group)
{
FAR struct child_status_s *curr;
FAR struct child_status_s *next;
/* Remove all child structures for the TCB and return them to the freelist */
- for (curr = tcb->children; curr; curr = next)
+ for (curr = group->tg_children; curr; curr = next)
{
next = curr->flink;
- task_freechild(curr);
+ group_freechild(curr);
}
- tcb->children = NULL;
- task_dumpchildren(tcb, "task_removechildren");
+ group->tg_children = NULL;
+ group_dumpchildren(group, "group_removechildren");
}
#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */
diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c
new file mode 100644
index 000000000..24f6923aa
--- /dev/null
+++ b/nuttx/sched/group_create.c
@@ -0,0 +1,276 @@
+/*****************************************************************************
+ * sched/group_create.c
+ *
+ * Copyright (C) 2013 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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+/* Is this worth making a configuration option? */
+
+#define GROUP_INITIAL_MEMBERS 4
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+/* This is counter that is used to generate unique task group IDs */
+
+#ifdef HAVE_GROUP_MEMBERS
+static gid_t g_gidcounter;
+#endif
+
+/*****************************************************************************
+ * Public Data
+ *****************************************************************************/
+/* This is the head of a list of all group members */
+
+#ifdef HAVE_GROUP_MEMBERS
+FAR struct task_group_s *g_grouphead;
+#endif
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_assigngid
+ *
+ * Description:
+ * Create a unique group ID.
+ *
+ * Parameters:
+ * tcb - The tcb in need of the task group.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * Called during task creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+void group_assigngid(FAR struct task_group_s *group)
+{
+ irqstate_t flags;
+ gid_t gid;
+
+ /* Pre-emption should already be enabled, but lets be paranoid careful */
+
+ sched_lock();
+
+ /* Loop until we create a unique ID */
+
+ for (;;)
+ {
+ /* Increment the ID counter. This is global data so be extra paraoid. */
+
+ flags = irqsave();
+ gid = ++g_gidcounter;
+
+ /* Check for overflow */
+
+ if (gid <= 0)
+ {
+ g_gidcounter = 1;
+ irqrestore(flags);
+ }
+ else
+ {
+ /* Does a task group with this ID already exist? */
+
+ irqrestore(flags);
+ if (group_find(gid) == NULL)
+ {
+ /* Now assign this ID to the group and return */
+
+ group->tg_gid = gid;
+ sched_unlock();
+ return;
+ }
+ }
+ }
+}
+#endif /* HAVE_GROUP_MEMBERS */
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_allocate
+ *
+ * Description:
+ * Create and a new task group structure for the specified TCB. This
+ * function is called as part of the task creation sequence. The structure
+ * allocated and zered, but otherwise uninitialized. The full creation
+ * of the group of a two step process: (1) First, this function allocates
+ * group structure early in the task creation sequence in order to provide a
+ * group container, then (2) group_initialize() is called to set up the
+ * group membership.
+ *
+ * Parameters:
+ * tcb - The tcb in need of the task group.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_allocate(FAR _TCB *tcb)
+{
+ int ret;
+
+ DEBUGASSERT(tcb && !tcb->group);
+
+ /* Allocate the group structure and assign it to the TCB */
+
+ tcb->group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s));
+ if (!tcb->group)
+ {
+ return -ENOMEM;
+ }
+
+ /* Assign the group a unique ID. If g_gidcounter were to wrap before we
+ * finish with task creation, that would be a problem.
+ */
+
+#ifdef HAVE_GROUP_MEMBERS
+ group_assigngid(tcb->group);
+#endif
+
+ /* Duplicate the parent tasks envionment */
+
+ ret = env_dup(tcb->group);
+ if (ret < 0)
+ {
+ kfree(tcb->group);
+ tcb->group = NULL;
+ return ret;
+ }
+
+ return OK;
+}
+
+/*****************************************************************************
+ * Name: group_initialize
+ *
+ * Description:
+ * Add the task as the initial member of the group. The full creation of
+ * the group of a two step process: (1) First, this group structure is
+ * allocated by group_allocate() early in the task creation sequence, then
+ * (2) this function is called to set up the initial group membership.
+ *
+ * Parameters:
+ * tcb - The tcb in need of the task group.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_initialize(FAR _TCB *tcb)
+{
+ FAR struct task_group_s *group;
+#ifdef HAVE_GROUP_MEMBERS
+ irqstate_t flags;
+#endif
+
+ DEBUGASSERT(tcb && tcb->group);
+ group = tcb->group;
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */
+
+ group->tg_members = (FAR pid_t *)kmalloc(GROUP_INITIAL_MEMBERS*sizeof(pid_t));
+ if (!group->tg_members)
+ {
+ free(group);
+ return -ENOMEM;
+ }
+
+ /* Assign the PID of this new task as a member of the group*/
+
+ group->tg_members[0] = tcb->pid;
+
+ /* Initialize the non-zero elements of group structure and assign it to
+ * the tcb.
+ */
+
+ group->tg_mxmembers = GROUP_INITIAL_MEMBERS; /* Number of members in allocation */
+
+ /* Add the initialized entry to the list of groups */
+
+ flags = irqsave();
+ group->flink = g_grouphead;
+ g_grouphead = group;
+ irqrestore(flags);
+
+#endif
+
+ group->tg_nmembers = 1; /* Number of members in the group */
+ return OK;
+}
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/group_find.c b/nuttx/sched/group_find.c
new file mode 100644
index 000000000..eb3989223
--- /dev/null
+++ b/nuttx/sched/group_find.c
@@ -0,0 +1,125 @@
+/*****************************************************************************
+ * sched/group_find.c
+ *
+ * Copyright (C) 2013 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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Public Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_find
+ *
+ * Description:
+ * Given a group ID, find the group task structure with that ID. IDs are
+ * used instead of pointers to group structures. This is done because a
+ * group can disappear at any time leaving a stale pointer; an ID is cleaner
+ * because if the group disappears, this function will fail gracefully.
+ *
+ * Parameters:
+ * gid - The group ID to find.
+ *
+ * Return Value:
+ * On success, a pointer to the group task structure is returned. This
+ * function can fail only if there is no group that corresponds to the
+ * groupd ID.
+ *
+ * Assumptions:
+ * Called during when signally tasks in a safe context. No special
+ * precautions should be required here. However, extra care is taken when
+ * accessing the global g_grouphead list.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+FAR struct task_group_s *group_find(gid_t gid)
+{
+ FAR struct task_group_s *group;
+ irqstate_t flags;
+
+ /* Find the status structure with the matching PID */
+
+ flags = irqsave();
+ for (group = g_grouphead; group; group = group->flink)
+ {
+ if (group->tg_gid == gid)
+ {
+ irqrestore(flags);
+ return group;
+ }
+ }
+
+ irqrestore(flags);
+ return NULL;
+}
+#endif
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/group_internal.h
index 648d9273e..ca6aacff7 100644
--- a/nuttx/sched/sched_setuppthreadfiles.c
+++ b/nuttx/sched/group_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched_setuppthreadfiles.c
+ * sched/group_internal.h
*
- * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,76 +33,94 @@
*
****************************************************************************/
+#ifndef __SCHED_GROUP_INERNAL_H
+#define __SCHED_GROUP_INERNAL_H
+
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
+#include <sys/types.h>
+#include <stdbool.h>
+#include <queue.h>
#include <sched.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/net/net.h>
-#include <nuttx/lib.h>
-
-#include "os_internal.h"
-
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+#include <nuttx/kmalloc.h>
/****************************************************************************
- * Private Functions
+ * Pre-processor Definitions
****************************************************************************/
+/* Any negative GID is invalid. */
+
+#define INVALID_GROUP_ID (pid_t)-1
+#define IS_INVALID_GID(gid) ((int)(gid) < 0)
/****************************************************************************
- * Public Functions
+ * Public Type Definitions
****************************************************************************/
/****************************************************************************
- * Name: sched_setuppthreadfiles
- *
- * Description:
- * Configure a newly allocated TCB so that it will inherit file
- * descriptors and streams from the parent pthread.
- *
- * Parameters:
- * tcb - tcb of the new task.
- *
- * Return Value:
- * OK (if an error were returned, it would need to be a non-negated
- * errno value).
- *
- * Assumptions:
- *
+ * Public Data
****************************************************************************/
+/* This is the head of a list of all group members */
-int sched_setuppthreadfiles(FAR _TCB *tcb)
-{
- FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+#ifdef HAVE_GROUP_MEMBERS
+extern FAR struct task_group_s *g_grouphead;
+#endif
-#if CONFIG_NFILE_DESCRIPTORS > 0
- /* The child thread inherits the parent file descriptors */
-
- tcb->filelist = rtcb->filelist;
- files_addreflist(tcb->filelist);
-
-#endif /* CONFIG_NFILE_DESCRIPTORS */
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- /* The child thread inherits the parent socket descriptors */
-
- tcb->sockets = rtcb->sockets;
- net_addreflist(tcb->sockets);
-
-#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/* Task group data structure management */
+
+#ifdef HAVE_TASK_GROUP
+int group_allocate(FAR _TCB *tcb);
+int group_initialize(FAR _TCB *tcb);
+int group_bind(FAR _TCB *tcb);
+int group_join(FAR _TCB *tcb);
+void group_leave(FAR _TCB *tcb);
+
+#ifdef HAVE_GROUP_MEMBERS
+FAR struct task_group_s *group_find(gid_t gid);
+int group_addmember(FAR struct task_group_s *group, pid_t pid);
+int group_removemember(FAR struct task_group_s *group, pid_t pid);
+#endif
+
+#ifndef CONFIG_DISABLE_SIGNALS
+int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info);
+#endif
+#endif /* HAVE_TASK_GROUP */
+
+/* Parent/child data management */
+
+#ifdef CONFIG_SCHED_HAVE_PARENT
+int task_reparent(pid_t ppid, pid_t chpid);
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+FAR struct child_status_s *group_allocchild(void);
+void group_freechild(FAR struct child_status_s *status);
+void group_addchild(FAR struct task_group_s *group,
+ FAR struct child_status_s *child);
+FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group);
+FAR struct child_status_s *group_findchild(FAR struct task_group_s *group,
+ pid_t pid);
+FAR struct child_status_s *group_removechild(FAR struct task_group_s *group,
+ pid_t pid);
+void group_removechildren(FAR struct task_group_s *group);
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+#endif /* CONFIG_SCHED_HAVE_PARENT */
+
+/* Group data resource configuration */
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+int group_setupidlefiles(FAR _TCB *tcb);
+int group_setuptaskfiles(FAR _TCB *tcb);
#if CONFIG_NFILE_STREAMS > 0
- /* The child thread inherits the parent streams */
-
- tcb->streams = rtcb->streams;
- lib_addreflist(tcb->streams);
-
-#endif /* CONFIG_NFILE_STREAMS */
- return OK;
-}
+int group_setupstreams(FAR _TCB *tcb);
+#endif
+#endif
-#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
+#endif /* __SCHED_GROUP_INERNAL_H */
diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c
new file mode 100644
index 000000000..70319b3a1
--- /dev/null
+++ b/nuttx/sched/group_join.c
@@ -0,0 +1,227 @@
+/*****************************************************************************
+ * sched/group_join.c
+ *
+ * Copyright (C) 2013 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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+/* Is this worth making a configuration option? */
+
+#define GROUP_REALLOC_MEMBERS 4
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_bind
+ *
+ * Description:
+ * A thread joins the group when it is created. This is a two step process,
+ * first, the group must bound to the new threads TCB. group_bind() does
+ * this (at the return from group_join, things are a little unstable: The
+ * group has been bound, but tg_nmembers hs not yet been incremented).
+ * Then, after the new thread is initialized and has a PID assigned to it,
+ * group_join() is called, incrementing the tg_nmembers count on the group.
+ *
+ * Parameters:
+ * tcb - The TCB of the new "child" task that need to join the group.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * - The parent task from which the group will be inherited is the task at
+ * the thead of the ready to run list.
+ * - Called during thread creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_bind(FAR _TCB *tcb)
+{
+ FAR _TCB *ptcb = (FAR _TCB *)g_readytorun.head;
+
+ DEBUGASSERT(ptcb && tcb && ptcb->group && !tcb->group);
+
+ /* Copy the group reference from the parent to the child */
+
+ tcb->group = ptcb->group;
+ return OK;
+}
+
+/*****************************************************************************
+ * Name: group_join
+ *
+ * Description:
+ * A thread joins the group when it is created. This is a two step process,
+ * first, the group must bound to the new threads TCB. group_bind() does
+ * this (at the return from group_join, things are a little unstable: The
+ * group has been bound, but tg_nmembers hs not yet been incremented).
+ * Then, after the new thread is initialized and has a PID assigned to it,
+ * group_join() is called, incrementing the tg_nmembers count on the group.
+ *
+ * Parameters:
+ * tcb - The TCB of the new "child" task that need to join the group.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * - The parent task from which the group will be inherited is the task at
+ * the thead of the ready to run list.
+ * - Called during thread creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_join(FAR _TCB *tcb)
+{
+ FAR struct task_group_s *group;
+#ifdef HAVE_GROUP_MEMBERS
+ int ret;
+#endif
+
+ DEBUGASSERT(tcb && tcb->group &&
+ tcb->group->tg_nmembers < UINT8_MAX);
+
+ /* Get the group from the TCB */
+
+ group = tcb->group;
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Add the member to the group */
+
+ ret = group_addmember(group, tcb->pid);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#endif
+
+ group->tg_nmembers++;
+ return OK;
+}
+
+/*****************************************************************************
+ * Name: group_addmember
+ *
+ * Description:
+ * Add a new member to a group.
+ *
+ * Parameters:
+ * group - The task group to add the new member
+ * pid - The new member
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during thread creation and during reparenting in a safe context.
+ * No special precautions are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+int group_addmember(FAR struct task_group_s *group, pid_t pid)
+{
+ DEBUGASSERT(group && group->tg_nmembers < UINT8_MAX);
+
+ /* Will we need to extend the size of the array of groups? */
+
+ if (group->tg_nmembers >= group->tg_mxmembers)
+ {
+ FAR pid_t *newmembers;
+ unsigned int newmax;
+
+ /* Yes... reallocate the array of members */
+
+ newmax = group->tg_mxmembers + GROUP_REALLOC_MEMBERS;
+ if (newmax > UINT8_MAX)
+ {
+ newmax = UINT8_MAX;
+ }
+
+ newmembers = (FAR pid_t *)
+ krealloc(group->tg_members, sizeof(pid_t) * newmax);
+
+ if (!newmembers)
+ {
+ return -ENOMEM;
+ }
+
+ /* Save the new number of members in the reallocated members array */
+
+ group->tg_members = newmembers;
+ group->tg_mxmembers = newmax;
+ }
+
+ /* Assign this new pid to the group. */
+
+ group->tg_members[group->tg_nmembers] = pid;
+ return OK;
+}
+#endif /* HAVE_GROUP_MEMBERS */
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c
new file mode 100644
index 000000000..4dec30633
--- /dev/null
+++ b/nuttx/sched/group_leave.c
@@ -0,0 +1,366 @@
+/*****************************************************************************
+ * sched/group_leave.c
+ *
+ * Copyright (C) 2013 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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/fs/fs.h>
+#include <nuttx/net/net.h>
+#include <nuttx/lib.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_remove
+ *
+ * Description:
+ * Remove a group from the list of groups.
+ *
+ * Parameters:
+ * group - The group to be removed.
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * Called during task deletion in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+void group_remove(FAR struct task_group_s *group)
+{
+ FAR struct task_group_s *curr;
+ FAR struct task_group_s *prev;
+ irqstate_t flags;
+
+ /* Let's be especially careful while access the global task group list.
+ * This is probably un-necessary.
+ */
+
+ flags = irqsave();
+
+ /* Find the task group structure */
+
+ for (prev = NULL, curr = g_grouphead;
+ curr && curr != group;
+ prev = curr, curr = curr->flink);
+
+ /* Did we find it? If so, remove it from the list. */
+
+ if (curr)
+ {
+ /* Do we remove it from mid-list? Or from the head of the list? */
+
+ if (prev)
+ {
+ prev->flink = curr->flink;
+ }
+ else
+ {
+ g_grouphead = curr->flink;
+ }
+
+ curr->flink = NULL;
+ }
+
+ irqrestore(flags);
+}
+#endif
+
+/*****************************************************************************
+ * Name: group_release
+ *
+ * Description:
+ * Release group resources after the last member has left the group.
+ *
+ * Parameters:
+ * group - The group to be removed.
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * Called during task deletion in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+static inline void group_release(FAR struct task_group_s *group)
+{
+ /* Free all un-reaped child exit status */
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+ group_removechildren(group);
+#endif
+
+ /* Free all file-related resources now. We really need to close files as
+ * soon as possible while we still have a functioning task.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ /* Free resources held by the file descriptor list */
+
+ files_releaselist(&group->tg_filelist);
+
+#if CONFIG_NFILE_STREAMS > 0
+ /* Free resource held by the stream list */
+
+ lib_releaselist(&group->tg_streamlist);
+
+#endif /* CONFIG_NFILE_STREAMS */
+#endif /* CONFIG_NFILE_DESCRIPTORS */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ /* Free resource held by the socket list */
+
+ net_releaselist(&group->tg_socketlist);
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+
+ /* Release all shared environment variables */
+
+#ifndef CONFIG_DISABLE_ENVIRON
+ env_release(group);
+#endif
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Remove the group from the list of groups */
+
+ group_remove(group);
+
+ /* Release the members array */
+
+ if (group->tg_members)
+ {
+ sched_free(group->tg_members);
+ group->tg_members = NULL;
+ }
+#endif
+
+ /* Release the group container itself */
+
+ sched_free(group);
+}
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_leave
+ *
+ * Description:
+ * Release a reference on a group. This function is called when a task or
+ * thread exits. It decrements the reference count on the group. If the
+ * reference count decrements to zero, then it frees the group and all of
+ * resources contained in the group.
+ *
+ * Parameters:
+ * tcb - The TCB of the task that is exiting.
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * Called during task deletion in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+void group_leave(FAR _TCB *tcb)
+{
+ FAR struct task_group_s *group;
+
+ DEBUGASSERT(tcb);
+
+ /* Make sure that we have a group */
+
+ group = tcb->group;
+ if (group)
+ {
+ /* Remove the member from group */
+
+ int ret = group_removemember(group, tcb->pid);
+ DEBUGASSERT(ret >= 0);
+
+ /* Is the group now empty? */
+
+ if (ret == 0)
+ {
+ /* Release all of the resource held by the task group */
+
+ group_release(group);
+ }
+
+ /* In any event, we can detach the group from the TCB so that we won't
+ * do this again.
+ */
+
+ tcb->group = NULL;
+ }
+}
+
+#else /* HAVE_GROUP_MEMBERS */
+
+void group_leave(FAR _TCB *tcb)
+{
+ FAR struct task_group_s *group;
+
+ DEBUGASSERT(tcb);
+
+ /* Make sure that we have a group */
+
+ group = tcb->group;
+ if (group)
+ {
+ /* Yes, we have a group.. Is this the last member of the group? */
+
+ if (group->tg_nmembers > 1)
+ {
+ /* No.. just decrement the number of members in the group */
+
+ group->tg_nmembers--;
+ }
+
+ /* Yes.. that was the last member remaining in the group */
+
+ else
+ {
+ /* Release all of the resource held by the task group */
+
+ group_release(group);
+ }
+
+ /* In any event, we can detach the group from the TCB so we won't do
+ * this again.
+ */
+
+ tcb->group = NULL;
+ }
+}
+
+#endif /* HAVE_GROUP_MEMBERS */
+
+/*****************************************************************************
+ * Name: group_removemember
+ *
+ * Description:
+ * Remove a member from a group.
+ *
+ * Parameters:
+ * group - The group from which to remove the member.
+ * pid - The member to be removed.
+ *
+ * Return Value:
+ * On success, returns the number of members remaining in the group (>=0).
+ * Can fail only if the member is not found in the group. On failure,
+ * returns -ENOENT
+ *
+ * Assumptions:
+ * Called during task deletion and also from the reparenting logic, both
+ * in a safe context. No special precautions are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+int group_removemember(FAR struct task_group_s *group, pid_t pid)
+{
+ int i;
+
+ DEBUGASSERT(group);
+
+ /* Find the member in the array of members and remove it */
+
+ for (i = 0; i < group->tg_nmembers; i++)
+ {
+ /* Does this member have the matching pid */
+
+ if (group->tg_members[i] == pid)
+ {
+ /* Yes.. break out of the loop. We don't do the actual
+ * removal here, instead we re-test i and do the adjustments
+ * outside of the loop. We do this because we want the
+ * DEBUGASSERT to work properly.
+ */
+
+ break;
+ }
+ }
+
+ /* Now, test if we found the task in the array of members. */
+
+ if (i < group->tg_nmembers)
+ {
+ /* Remove the member from the array of members */
+
+ group->tg_members[i] = group->tg_members[group->tg_nmembers - 1];
+ group->tg_nmembers--;
+ return group->tg_nmembers;
+ }
+
+ return -ENOENT;
+}
+#endif /* HAVE_GROUP_MEMBERS */
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c
index ae814e1a6..ceb9f3e2c 100644
--- a/nuttx/sched/sched_setupidlefiles.c
+++ b/nuttx/sched/group_setupidlefiles.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sched_setupidlefiles.c
+ * sched/group_setupidlefiles.c
*
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -50,6 +50,7 @@
#include <nuttx/net/net.h>
#include "os_internal.h"
+#include "group_internal.h"
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
@@ -62,7 +63,7 @@
****************************************************************************/
/****************************************************************************
- * Name: sched_setupidlefiles
+ * Name: group_setupidlefiles
*
* Description:
* Configure the idle thread's TCB.
@@ -77,30 +78,29 @@
*
****************************************************************************/
-int sched_setupidlefiles(FAR _TCB *tcb)
+int group_setupidlefiles(FAR _TCB *tcb)
{
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
+ FAR struct task_group_s *group = tcb->group;
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE)
int fd;
#endif
- /* Allocate file descriptors for the TCB */
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
+ DEBUGASSERT(group);
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0
- tcb->filelist = files_alloclist();
- if (!tcb->filelist)
- {
- return -ENOMEM;
- }
+ /* Initialize file descriptors for the TCB */
+
+ files_initlist(&group->tg_filelist);
#endif
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
/* Allocate socket descriptors for the TCB */
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- tcb->sockets = net_alloclist();
- if (!tcb->sockets)
- {
- return -ENOMEM;
- }
+ net_initlist(&group->tg_socketlist);
#endif
/* Open stdin, dup to get stdout and stderr. This should always
@@ -139,7 +139,7 @@ int sched_setupidlefiles(FAR _TCB *tcb)
/* Allocate file/socket streams for the TCB */
#if CONFIG_NFILE_STREAMS > 0
- return sched_setupstreams(tcb);
+ return group_setupstreams(tcb);
#else
return OK;
#endif
diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/group_setupstreams.c
index 22895b047..08399ae41 100644
--- a/nuttx/sched/sched_setupstreams.c
+++ b/nuttx/sched/group_setupstreams.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched_setupstreams.c
+ * group_setupstreams.c
*
- * Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2010-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,6 +46,8 @@
#include <nuttx/net/net.h>
#include <nuttx/lib.h>
+#include "group_internal.h"
+
/* Make sure that there are file or socket descriptors in the system and
* that some number of streams have been configured.
*/
@@ -62,7 +64,7 @@
****************************************************************************/
/****************************************************************************
- * Name: sched_setupstreams
+ * Name: group_setupstreams
*
* Description:
* Setup streams data structures that may be used for standard C buffered
@@ -70,26 +72,25 @@
*
****************************************************************************/
-int sched_setupstreams(FAR _TCB *tcb)
+int group_setupstreams(FAR _TCB *tcb)
{
- /* Allocate file streams for the TCB */
-
- tcb->streams = lib_alloclist();
- if (tcb->streams)
- {
- /* fdopen to get the stdin, stdout and stderr streams.
- * The following logic depends on the fact that the library
- * layer will allocate FILEs in order.
- *
- * fd = 0 is stdin (read-only)
- * fd = 1 is stdout (write-only, append)
- * fd = 2 is stderr (write-only, append)
- */
-
- (void)fs_fdopen(0, O_RDONLY, tcb);
- (void)fs_fdopen(1, O_WROK|O_CREAT, tcb);
- (void)fs_fdopen(2, O_WROK|O_CREAT, tcb);
- }
+ DEBUGASSERT(tcb && tcb->group);
+
+ /* Initialize file streams for the task group */
+
+ lib_streaminit(&tcb->group->tg_streamlist);
+
+ /* fdopen to get the stdin, stdout and stderr streams. The following logic
+ * depends on the fact that the library layer will allocate FILEs in order.
+ *
+ * fd = 0 is stdin (read-only)
+ * fd = 1 is stdout (write-only, append)
+ * fd = 2 is stderr (write-only, append)
+ */
+
+ (void)fs_fdopen(0, O_RDONLY, tcb);
+ (void)fs_fdopen(1, O_WROK|O_CREAT, tcb);
+ (void)fs_fdopen(2, O_WROK|O_CREAT, tcb);
return OK;
}
diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c
index d01b8d4cd..e2e7d4634 100644
--- a/nuttx/sched/sched_setuptaskfiles.c
+++ b/nuttx/sched/group_setuptaskfiles.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sched_setuptaskfiles.c
+ * sched/group_setuptaskfiles.c
*
- * Copyright (C) 2007-2008, 2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,6 +46,7 @@
#include <nuttx/net/net.h>
#include "os_internal.h"
+#include "group_internal.h"
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
@@ -93,34 +94,33 @@ static inline void sched_dupfiles(FAR _TCB *tcb)
FAR struct file *child;
int i;
+ DEBUGASSERT(tcb && tcb->group && rtcb->group);
+
/* Duplicate the file descriptors. This will be either all of the
* file descriptors or just the first three (stdin, stdout, and stderr)
* if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set
* accordingly above.
*/
- if (rtcb->filelist)
- {
- /* Get pointers to the parent and child task file lists */
+ /* Get pointers to the parent and child task file lists */
- parent = rtcb->filelist->fl_files;
- child = tcb->filelist->fl_files;
+ parent = rtcb->group->tg_filelist.fl_files;
+ child = tcb->group->tg_filelist.fl_files;
- /* Check each file in the parent file list */
+ /* Check each file in the parent file list */
- for (i = 0; i < NFDS_TOCLONE; i++)
- {
- /* Check if this file is opened by the parent. We can tell if
- * if the file is open because it contain a reference to a non-NULL
- * i-node structure.
- */
+ for (i = 0; i < NFDS_TOCLONE; i++)
+ {
+ /* Check if this file is opened by the parent. We can tell if
+ * if the file is open because it contain a reference to a non-NULL
+ * i-node structure.
+ */
- if (parent[i].f_inode)
- {
- /* Yes... duplicate it for the child */
+ if (parent[i].f_inode)
+ {
+ /* Yes... duplicate it for the child */
- (void)files_dup(&parent[i], &child[i]);
- }
+ (void)files_dup(&parent[i], &child[i]);
}
}
}
@@ -152,32 +152,31 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
FAR struct socket *child;
int i;
- /* Duplicate the socket descriptors of all sockets opened by the parent
- * task.
- */
+ /* Duplicate the socket descriptors of all sockets opened by the parent
+ * task.
+ */
- if (rtcb->sockets)
- {
- /* Get pointers to the parent and child task socket lists */
+ DEBUGASSERT(tcb && tcb->group && rtcb->group);
- parent = rtcb->sockets->sl_sockets;
- child = tcb->sockets->sl_sockets;
+ /* Get pointers to the parent and child task socket lists */
- /* Check each socket in the parent socket list */
+ parent = rtcb->group->tg_socketlist.sl_sockets;
+ child = tcb->group->tg_socketlist.sl_sockets;
- for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++)
- {
- /* Check if this parent socket is allocated. We can tell if the
- * socket is allocated because it will have a positive, non-zero
- * reference count.
- */
+ /* Check each socket in the parent socket list */
- if (parent[i].s_crefs > 0)
- {
- /* Yes... duplicate it for the child */
+ for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++)
+ {
+ /* Check if this parent socket is allocated. We can tell if the
+ * socket is allocated because it will have a positive, non-zero
+ * reference count.
+ */
+
+ if (parent[i].s_crefs > 0)
+ {
+ /* Yes... duplicate it for the child */
- (void)net_clone(&parent[i], &child[i]);
- }
+ (void)net_clone(&parent[i], &child[i]);
}
}
}
@@ -190,7 +189,7 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
****************************************************************************/
/****************************************************************************
- * Name: sched_setuptaskfiles
+ * Name: group_setuptaskfiles
*
* Description:
* Configure a newly allocated TCB so that it will inherit
@@ -207,26 +206,24 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
*
****************************************************************************/
-int sched_setuptaskfiles(FAR _TCB *tcb)
+int group_setuptaskfiles(FAR _TCB *tcb)
{
- /* Allocate file descriptors for the TCB */
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+ FAR struct task_group_s *group = tcb->group;
+
+ DEBUGASSERT(group);
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0
- tcb->filelist = files_alloclist();
- if (!tcb->filelist)
- {
- return -ENOMEM;
- }
+ /* Initialize file descriptors for the TCB */
+
+ files_initlist(&group->tg_filelist);
#endif
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
/* Allocate socket descriptors for the TCB */
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- tcb->sockets = net_alloclist();
- if (!tcb->sockets)
- {
- return -ENOMEM;
- }
+ net_initlist(&group->tg_socketlist);
#endif
/* Duplicate the parent task's file descriptors */
@@ -240,7 +237,7 @@ int sched_setuptaskfiles(FAR _TCB *tcb)
/* Allocate file/socket streams for the new TCB */
#if CONFIG_NFILE_STREAMS > 0
- return sched_setupstreams(tcb);
+ return group_setupstreams(tcb);
#else
return OK;
#endif
diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c
new file mode 100644
index 000000000..009ab7a55
--- /dev/null
+++ b/nuttx/sched/group_signal.c
@@ -0,0 +1,163 @@
+/*****************************************************************************
+ * sched/group_signal.c
+ *
+ * Copyright (C) 2013 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 <sched.h>
+#include <assert.h>
+#include <signal.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "sig_internal.h"
+
+#if defined(HAVE_TASK_GROUP) && !defined(CONFIG_DISABLE_SIGNALS)
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_signal
+ *
+ * Description:
+ * Send a signal to every member of the group.
+ *
+ * Parameters:
+ * group - The task group that needs to be signalled.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task terminatino in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ FAR _TCB *gtcb;
+ int i;
+
+ DEBUGASSERT(group && info);
+
+ /* Make sure that pre-emption is disabled to that we signal all of teh
+ * members of the group before any of them actually run.
+ */
+
+ sched_lock();
+
+ /* Send the signal to each member of the group */
+
+ for (i = 0; i < group->tg_nmembers; i++)
+ {
+ gtcb = sched_gettcb(group->tg_members[i]);
+ DEBUGASSERT(gtcb);
+ if (gtcb)
+ {
+ /* Use the sig_received interface so that it does not muck with
+ * the siginfo_t.
+ */
+
+#ifdef CONFIG_DEBUG
+ int ret = sig_received(gtcb, info);
+ DEBUGASSERT(ret == 0);
+#else
+ (void)sig_received(gtcb, info);
+#endif
+ }
+ }
+
+ /* Re-enable pre-emption an return success */
+
+ sched_unlock();
+ return OK;
+#else
+ return -ENOSYS;
+#endif
+}
+
+/*****************************************************************************
+ * Name: group_signalmember
+ *
+ * Description:
+ * Send a signal to every member of the group to which task belongs.
+ *
+ * Parameters:
+ * tcb - The tcb of one task in the task group that needs to be signalled.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task terminatino in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_signalmember(FAR _TCB *tcb, FAR siginfo_t *info)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ DEBUGASSERT(tcb);
+ return group_signal(tcb->group, info);
+#else
+ return sig_received(tcb, info);
+#endif
+}
+#endif /* HAVE_TASK_GROUP && !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/sched/mq_sndinternal.c b/nuttx/sched/mq_sndinternal.c
index 51f898875..f16f7de1a 100644
--- a/nuttx/sched/mq_sndinternal.c
+++ b/nuttx/sched/mq_sndinternal.c
@@ -124,7 +124,7 @@ int mq_verifysend(mqd_t mqdes, const void *msg, size_t msglen, int prio)
return ERROR;
}
- if (msglen < 0 || msglen > (size_t)mqdes->msgq->maxmsgsize)
+ if (msglen > (size_t)mqdes->msgq->maxmsgsize)
{
set_errno(EMSGSIZE);
return ERROR;
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 7d5095bad..262a40ccc 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -99,15 +99,6 @@ enum os_crash_codes_e
#define MAX_TASKS_MASK (CONFIG_MAX_TASKS-1)
#define PIDHASH(pid) ((pid) & MAX_TASKS_MASK)
-/* Stubs used when there are no file descriptors */
-
-#if CONFIG_NFILE_DESCRIPTORS <= 0 && CONFIG_NSOCKET_DESCRIPTORS <= 0
-# define sched_setupidlefiles(t) (OK)
-# define sched_setuptaskfiles(t) (OK)
-# define sched_setuppthreadfiles(t) (OK)
-# define sched_releasefiles(t) (OK)
-#endif
-
/* One processor family supported by NuttX has a single, fixed hardware stack.
* That is the 8051 family. So for that family only, there is a variant form
* of kernel_thread() that does not take a stack size parameter. The following
@@ -262,24 +253,16 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
****************************************************************************/
int os_bringup(void);
+#ifdef CONFIG_SCHED_CHILD_STATUS
+void weak_function task_initialize(void);
+#endif
void task_start(void);
int task_schedsetup(FAR _TCB *tcb, int priority, start_t start,
main_t main, uint8_t ttype);
int task_argsetup(FAR _TCB *tcb, FAR const char *name, FAR const char *argv[]);
void task_exithook(FAR _TCB *tcb, int status);
int task_deletecurrent(void);
-#ifdef CONFIG_SCHED_HAVE_PARENT
-#ifdef CONFIG_SCHED_CHILD_STATUS
-void weak_function task_initialize(void);
-FAR struct child_status_s *task_allocchild(void);
-void task_freechild(FAR struct child_status_s *status);
-void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child);
-FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid);
-FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid);
-void task_removechildren(FAR _TCB *tcb);
-#endif
-int task_reparent(pid_t ppid, pid_t chpid);
-#endif
+
#ifndef CONFIG_CUSTOM_STACK
int kernel_thread(FAR const char *name, int priority, int stack_size,
main_t entry, FAR const char *argv[]);
@@ -302,16 +285,6 @@ int sched_reprioritize(FAR _TCB *tcb, int sched_priority);
FAR _TCB *sched_gettcb(pid_t pid);
bool sched_verifytcb(FAR _TCB *tcb);
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
-int sched_setupidlefiles(FAR _TCB *tcb);
-int sched_setuptaskfiles(FAR _TCB *tcb);
-int sched_setuppthreadfiles(FAR _TCB *tcb);
-#if CONFIG_NFILE_STREAMS > 0
-int sched_setupstreams(FAR _TCB *tcb);
-#endif
-int sched_releasefiles(FAR _TCB *tcb);
-#endif
-
int sched_releasetcb(FAR _TCB *tcb);
void sched_garbagecollection(void);
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index a6d4e83b9..c60edc495 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/os_start.c
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -63,6 +63,9 @@
#include "clock_internal.h"
#include "timer_internal.h"
#include "irq_internal.h"
+#ifdef HAVE_TASK_GROUP
+#include "group_internal.h"
+#endif
/****************************************************************************
* Pre-processor Definitions
@@ -286,7 +289,6 @@ void os_start(void)
/* Initialize the processor-specific portion of the TCB */
- g_idletcb.flags = (TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_NOCLDWAIT);
up_initial_state(&g_idletcb);
/* Initialize the semaphore facility(if in link). This has to be done
@@ -325,6 +327,12 @@ void os_start(void)
}
#endif
+ /* Allocate the IDLE group and suppress child status. */
+
+#ifdef HAVE_TASK_GROUP
+ (void)group_allocate(&g_idletcb);
+#endif
+
/* Initialize the interrupt handling subsystem (if included) */
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
@@ -441,7 +449,16 @@ void os_start(void)
* inherited by all of the threads created by the IDLE task.
*/
- (void)sched_setupidlefiles(&g_idletcb);
+ (void)group_setupidlefiles(&g_idletcb);
+
+ /* Complete initialization of the IDLE group. Suppress retention
+ * of child status in the IDLE group.
+ */
+
+#ifdef HAVE_TASK_GROUP
+ (void)group_initialize(&g_idletcb);
+ g_idletcb.group->tg_flags = GROUP_FLAG_NOCLDWAIT;
+#endif
/* Create initial tasks and bring-up the system */
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index f4d0d8fdf..48a0788a6 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -53,8 +53,8 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "clock_internal.h"
-#include "env_internal.h"
#include "pthread_internal.h"
/****************************************************************************
@@ -246,12 +246,13 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
{
FAR _TCB *ptcb;
FAR join_t *pjoin;
- int ret;
int priority;
#if CONFIG_RR_INTERVAL > 0
int policy;
#endif
+ int errcode;
pid_t pid;
+ int ret;
/* If attributes were not supplied, use the default attributes */
@@ -268,6 +269,19 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
return ENOMEM;
}
+ /* Bind the parent's group to the new TCB (we have not yet joined the
+ * group).
+ */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_bind(ptcb);
+ if (ret < 0)
+ {
+ errcode = ENOMEM;
+ goto errout_with_tcb;
+ }
+#endif
+
/* Share the address environment of the parent task. NOTE: Only tasks
* created throught the nuttx/binfmt loaders may have an address
* environment.
@@ -277,31 +291,18 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
ret = up_addrenv_share((FAR const _TCB *)g_readytorun.head, ptcb);
if (ret < 0)
{
- sched_releasetcb(ptcb);
- return -ret;
+ errcode = -ret;
+ goto errout_with_tcb;
}
#endif
- /* Associate file descriptors with the new task */
-
- ret = sched_setuppthreadfiles(ptcb);
- if (ret != OK)
- {
- sched_releasetcb(ptcb);
- return ret;
- }
-
- /* Share the parent's envionment */
-
- (void)env_share(ptcb);
-
/* Allocate a detachable structure to support pthread_join logic */
pjoin = (FAR join_t*)kzalloc(sizeof(join_t));
if (!pjoin)
{
- sched_releasetcb(ptcb);
- return ENOMEM;
+ errcode = ENOMEM;
+ goto errout_with_tcb;
}
/* Allocate the stack for the TCB */
@@ -309,9 +310,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
ret = up_create_stack(ptcb, attr->stacksize);
if (ret != OK)
{
- sched_releasetcb(ptcb);
- sched_free(pjoin);
- return ENOMEM;
+ errcode = ENOMEM;
+ goto errout_with_join;
}
/* Should we use the priority and scheduler specified in the
@@ -360,9 +360,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
TCB_FLAG_TTYPE_PTHREAD);
if (ret != OK)
{
- sched_releasetcb(ptcb);
- sched_free(pjoin);
- return EBUSY;
+ errcode = EBUSY;
+ goto errout_with_join;
}
/* Configure the TCB for a pthread receiving on parameter
@@ -371,6 +370,17 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
pthread_argsetup(ptcb, arg);
+ /* Join the parent's task group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_join(ptcb);
+ if (ret < 0)
+ {
+ errcode = ENOMEM;
+ goto errout_with_join;
+ }
+#endif
+
/* Attach the join info to the TCB. */
ptcb->joininfo = (void*)pjoin;
@@ -440,10 +450,18 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
dq_rem((FAR dq_entry_t*)ptcb, (dq_queue_t*)&g_inactivetasks);
(void)sem_destroy(&pjoin->data_sem);
(void)sem_destroy(&pjoin->exit_sem);
- sched_releasetcb(ptcb);
- sched_free(pjoin);
- ret = EIO;
+
+ errcode = EIO;
+ goto errout_with_join;
}
return ret;
+
+errout_with_join:
+ sched_free(pjoin);
+ ptcb->joininfo = NULL;
+
+errout_with_tcb:
+ sched_releasetcb(ptcb);
+ return errcode;
}
diff --git a/nuttx/sched/pthread_join.c b/nuttx/sched/pthread_join.c
index 6a02af352..d3f648dc7 100644
--- a/nuttx/sched/pthread_join.c
+++ b/nuttx/sched/pthread_join.c
@@ -123,7 +123,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value)
* This can fail for one of three reasons: (1) There is no
* thread associated with 'thread,' (2) the thread is a task
* and does not have join information, or (3) the thread
- * was detached and has exitted.
+ * was detached and has exited.
*/
pjoin = pthread_findjoininfo((pid_t)thread);
diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c
index 256b4cb6b..17ca2bbf6 100644
--- a/nuttx/sched/sched_getfiles.c
+++ b/nuttx/sched/sched_getfiles.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_getfiles.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -70,7 +70,10 @@
FAR struct filelist *sched_getfiles(void)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- return rtcb->filelist;
+ FAR struct task_group_s *group = rtcb->group;
+
+ DEBUGASSERT(group);
+ return &group->tg_filelist;
}
#endif /* CONFIG_NFILE_DESCRIPTORS */
diff --git a/nuttx/sched/sched_getsockets.c b/nuttx/sched/sched_getsockets.c
index cd499420f..ea988d6ff 100644
--- a/nuttx/sched/sched_getsockets.c
+++ b/nuttx/sched/sched_getsockets.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_getsockets.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -71,7 +71,10 @@
FAR struct socketlist *sched_getsockets(void)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- return rtcb->sockets;
+ FAR struct task_group_s *group = rtcb->group;
+
+ DEBUGASSERT(group);
+ return &group->tg_socketlist;
}
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/sched/sched_getstreams.c b/nuttx/sched/sched_getstreams.c
index f7c21ab4c..dab406e66 100644
--- a/nuttx/sched/sched_getstreams.c
+++ b/nuttx/sched/sched_getstreams.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/sched_getstreams.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -70,7 +70,10 @@
FAR struct streamlist *sched_getstreams(void)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- return rtcb->streams;
+ FAR struct task_group_s *group = rtcb->group;
+
+ DEBUGASSERT(group);
+ return &group->tg_streamlist;
}
#endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_NFILE_STREAMS */
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 0557c829b..02f7170c2 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_releasetcb.c
*
- * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -45,8 +45,8 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "timer_internal.h"
-#include "env_internal.h"
/************************************************************************
* Private Functions
@@ -163,20 +163,17 @@ int sched_releasetcb(FAR _TCB *tcb)
}
}
- /* Release any allocated file structures */
-
- ret = sched_releasefiles(tcb);
-
- /* Release environment variables */
-
- (void)env_release(tcb);
-
/* Release this thread's reference to the address environment */
#ifdef CONFIG_ADDRENV
ret = up_addrenv_release(tcb);
#endif
+ /* Leave the group (if we did not already leady in task_exithook.c) */
+
+#ifdef HAVE_TASK_GROUP
+ group_leave(tcb);
+#endif
/* And, finally, release the TCB itself */
sched_free(tcb);
diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c
index 37ee26ce0..9c24189c4 100644
--- a/nuttx/sched/sched_waitid.c
+++ b/nuttx/sched/sched_waitid.c
@@ -46,6 +46,7 @@
#include <nuttx/sched.h>
#include "os_internal.h"
+#include "group_internal.h"
#if defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT)
@@ -54,6 +55,36 @@
*****************************************************************************/
/*****************************************************************************
+ * Name: exited_child
+ *
+ * Description:
+ * Handle the case where a child exited properlay was we (apparently) lost
+ * the detch of child signal.
+ *
+ *****************************************************************************/
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+static void exited_child(FAR _TCB *rtcb, FAR struct child_status_s *child,
+ FAR siginfo_t *info)
+{
+ /* The child has exited. Return the saved exit status (and some fudged
+ * information.
+ */
+
+ info->si_signo = SIGCHLD;
+ info->si_code = CLD_EXITED;
+ info->si_value.sival_ptr = NULL;
+ info->si_pid = child->ch_pid;
+ info->si_status = child->ch_status;
+
+ /* Discard the child entry */
+
+ (void)group_removechild(rtcb->group, child->ch_pid);
+ group_freechild(child);
+}
+#endif
+
+/*****************************************************************************
* Public Functions
*****************************************************************************/
@@ -120,9 +151,14 @@
*
*****************************************************************************/
-int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
+int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options)
{
FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+ FAR _TCB *ctcb;
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ FAR struct child_status_s *child;
+ bool retains;
+#endif
sigset_t sigset;
int err;
int ret;
@@ -160,7 +196,11 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
*/
#ifdef CONFIG_SCHED_CHILD_STATUS
- if (rtcb->children == NULL)
+ /* Does this task retain child status? */
+
+ retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0);
+
+ if (rtcb->group->tg_children == NULL && retains)
{
/* There are no children */
@@ -169,13 +209,33 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
}
else if (idtype == P_PID)
{
- if (task_findchild(rtcb, (pid_t)id) == NULL)
- {
- /* This specific pid is not a child */
+ /* Get the TCB corresponding to this PID and make sure it is our child. */
+ ctcb = sched_gettcb((pid_t)id);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
+ {
err = ECHILD;
goto errout_with_errno;
}
+
+ /* Does this task retain child status? */
+
+ if (retains)
+ {
+ /* Check if this specific pid has allocated child status? */
+
+ if (group_findchild(rtcb->group, (pid_t)id) == NULL)
+ {
+ /* This specific pid is not a child */
+
+ err = ECHILD;
+ goto errout_with_errno;
+ }
+ }
}
#else
if (rtcb->nchildren == 0)
@@ -189,8 +249,12 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
{
/* Get the TCB corresponding to this PID and make sure it is our child. */
- FAR _TCB *ctcb = sched_gettcb((pid_t)id);
- if (!ctcb || ctcb->parent != rtcb->pid)
+ ctcb = sched_gettcb((pid_t)id);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
{
err = ECHILD;
goto errout_with_errno;
@@ -209,48 +273,61 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
* instead).
*/
- DEBUGASSERT(rtcb->children);
- if (rtcb->children == NULL)
+ DEBUGASSERT(!retains || rtcb->group->tg_children);
+ if (idtype == P_ALL)
{
- /* This should not happen. I am just wasting your FLASH. */
+ /* We are waiting for any child to exit */
- err = ECHILD;
- goto errout_with_errno;
- }
- else if (idtype == P_PID)
- {
- FAR struct child_status_s *child;
-
- /* We are waiting for a specific PID. Get the current status
- * of the child task.
- */
-
- child = task_findchild(rtcb, (pid_t)id);
- DEBUGASSERT(child);
- if (!child)
+ if (retains && (child = group_exitchild(rtcb->group)) != NULL)
{
- /* Yikes! The child status entry just disappeared! */
+ /* A child has exited. Apparently we missed the signal.
+ * Return the exit status and break out of the loop.
+ */
- err = ECHILD;
- goto errout_with_errno;
+ exited_child(rtcb, child, info);
+ break;
}
+ }
+ /* We are waiting for a specific PID. Does this task retain child status? */
+
+ else if (retains)
+ {
+ /* Yes ... Get the current status of the child task. */
+
+ child = group_findchild(rtcb->group, (pid_t)id);
+ DEBUGASSERT(child);
+
/* Did the child exit? */
if ((child->ch_flags & CHILD_FLAG_EXITED) != 0)
{
- /* The child has exited. Return the saved exit status */
+ /* The child has exited. Return the exit status and break out
+ * of the loop.
+ */
- info->si_signo = SIGCHLD;
- info->si_code = CLD_EXITED;
- info->si_value.sival_ptr = NULL;
- info->si_pid = (pid_t)id;
- info->si_status = child->ch_status;
+ exited_child(rtcb, child, info);
+ break;
+ }
+ }
+ else
+ {
+ /* We can use kill() with signal number 0 to determine if that
+ * task is still alive.
+ */
- /* Discard the child entry and break out of the loop */
+ ret = kill((pid_t)id, 0);
+ if (ret < 0)
+ {
+ /* It is no longer running. We know that the child task
+ * was running okay when we started, so we must have lost
+ * the signal. In this case, we know that the task exit'ed,
+ * but we do not know its exit status. It would be better
+ * to reported ECHILD than bogus status.
+ */
- (void)task_removechild(rtcb, (pid_t)id);
- task_freechild(child);
+ err = ECHILD;
+ goto errout_with_errno;
}
}
#else
diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c
index fe3f7167d..0285c2673 100644
--- a/nuttx/sched/sched_waitpid.c
+++ b/nuttx/sched/sched_waitpid.c
@@ -47,6 +47,7 @@
#include <nuttx/sched.h>
#include "os_internal.h"
+#include "group_internal.h"
#ifdef CONFIG_SCHED_WAITPID
@@ -171,21 +172,17 @@
*
* Assumptions:
*
- *****************************************************************************/
-
-/***************************************************************************
- * NOTE: This is a partially functional, experimental version of waitpid()
- *
- * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not
- * defined), then waitpid() is still available, but does not obey the
- * restriction that the pid be a child of the caller.
+ * Compatibility
+ * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not
+ * defined), then waitpid() is still available, but does not obey the
+ * restriction that the pid be a child of the caller.
*
- ***************************************************************************/
+ *****************************************************************************/
#ifndef CONFIG_SCHED_HAVE_PARENT
pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
- _TCB *tcb;
+ _TCB *ctcb;
bool mystat;
int err;
int ret;
@@ -208,8 +205,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
/* Get the TCB corresponding to this PID */
- tcb = sched_gettcb(pid);
- if (!tcb)
+ ctcb = sched_gettcb(pid);
+ if (!ctcb)
{
err = ECHILD;
goto errout_with_errno;
@@ -221,15 +218,15 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
* others?
*/
- if (stat_loc != NULL && tcb->stat_loc == NULL)
+ if (stat_loc != NULL && ctcb->stat_loc == NULL)
{
- tcb->stat_loc = stat_loc;
- mystat = true;
+ ctcb->stat_loc = stat_loc;
+ mystat = true;
}
/* Then wait for the task to exit */
- ret = sem_wait(&tcb->exitsem);
+ ret = sem_wait(&ctcb->exitsem);
if (ret < 0)
{
/* Unlock pre-emption and return the ERROR (sem_wait has already set
@@ -239,7 +236,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
if (mystat)
{
- tcb->stat_loc = NULL;
+ ctcb->stat_loc = NULL;
}
goto errout;
@@ -274,8 +271,10 @@ errout:
pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+ FAR _TCB *ctcb;
#ifdef CONFIG_SCHED_CHILD_STATUS
FAR struct child_status_s *child;
+ bool retains;
#endif
FAR struct siginfo info;
sigset_t sigset;
@@ -303,27 +302,47 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
sched_lock();
- /* Verify that this task actually has children and that the the request
- * TCB is actually a child of this task.
+ /* Verify that this task actually has children and that the requested PID
+ * is actually a child of this task.
*/
#ifdef CONFIG_SCHED_CHILD_STATUS
- if (rtcb->children == NULL)
- {
- /* There are no children */
+ /* Does this task retain child status? */
+ retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0);
+
+ if (rtcb->group->tg_children == NULL && retains)
+ {
err = ECHILD;
goto errout_with_errno;
}
else if (pid != (pid_t)-1)
{
- /* This specific pid is not a child */
+ /* Get the TCB corresponding to this PID and make sure it is our child. */
- if (task_findchild(rtcb, pid) == NULL)
+ ctcb = sched_gettcb(pid);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
{
err = ECHILD;
goto errout_with_errno;
}
+
+ /* Does this task retain child status? */
+
+ if (retains)
+ {
+ /* Check if this specific pid has allocated child status? */
+
+ if (group_findchild(rtcb->group, pid) == NULL)
+ {
+ err = ECHILD;
+ goto errout_with_errno;
+ }
+ }
}
#else
if (rtcb->nchildren == 0)
@@ -337,8 +356,12 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
/* Get the TCB corresponding to this PID and make sure it is our child. */
- FAR _TCB *ctcb = sched_gettcb(pid);
- if (!ctcb || ctcb->parent != rtcb->pid)
+ ctcb = sched_gettcb(pid);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
{
err = ECHILD;
goto errout_with_errno;
@@ -350,6 +373,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
for (;;)
{
+#ifdef CONFIG_SCHED_CHILD_STATUS
/* Check if the task has already died. Signals are not queued in
* NuttX. So a possibility is that the child has died and we
* missed the death of child signal (we got some other signal
@@ -362,39 +386,33 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
* chilren.
*/
-#ifdef CONFIG_SCHED_CHILD_STATUS
- DEBUGASSERT(rtcb->children);
- if (rtcb->children == NULL)
-#else
- if (rtcb->nchildren == 0)
-#endif
+ DEBUGASSERT(!retains || rtcb->group->tg_children);
+ if (retains && (child = group_exitchild(rtcb->group)) != NULL)
{
- /* There were one or more children when we started so they
- * must have exit'ed. There are just no bread crumbs left
- * behind to tell us the PID(s) of the existed children.
- * Reporting ECHLD is about all we can do in this case.
+ /* A child has exited. Apparently we missed the signal.
+ * Return the saved exit status.
*/
- err = ECHILD;
- goto errout_with_errno;
+ /* The child has exited. Return the saved exit status */
+
+ *stat_loc = child->ch_status << 8;
+
+ /* Discard the child entry and break out of the loop */
+
+ (void)group_removechild(rtcb->group, child->ch_pid);
+ group_freechild(child);
+ break;
}
}
- else
+
+ /* We are waiting for a specific PID. Does this task retain child status? */
+
+ else if (retains)
{
-#ifdef CONFIG_SCHED_CHILD_STATUS
- /* We are waiting for a specific PID. Get the current status
- * of the child task.
- */
+ /* Get the current status of the child task. */
- child = task_findchild(rtcb, pid);
+ child = group_findchild(rtcb->group, pid);
DEBUGASSERT(child);
- if (!child)
- {
- /* Yikes! The child status entry just disappeared! */
-
- err = ECHILD;
- goto errout_with_errno;
- }
/* Did the child exit? */
@@ -402,33 +420,54 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
/* The child has exited. Return the saved exit status */
- *stat_loc = child->ch_status;
+ *stat_loc = child->ch_status << 8;
/* Discard the child entry and break out of the loop */
- (void)task_removechild(rtcb, pid);
- task_freechild(child);
+ (void)group_removechild(rtcb->group, pid);
+ group_freechild(child);
+ break;
}
-#else
- /* We are waiting for a specific PID. We can use kill() with
- * signal number 0 to determine if that task is still alive.
+ }
+ else
+ {
+ /* We can use kill() with signal number 0 to determine if that
+ * task is still alive.
*/
ret = kill(pid, 0);
if (ret < 0)
{
- /* It is no longer running. We know that the child task was
- * running okay when we started, so we must have lost the
- * signal. In this case, we know that the task exit'ed, but
- * we do not know its exit status. It would be better to
- * reported ECHILD that bogus status.
+ /* It is no longer running. We know that the child task
+ * was running okay when we started, so we must have lost
+ * the signal. In this case, we know that the task exit'ed,
+ * but we do not know its exit status. It would be better
+ * to reported ECHILD than bogus status.
*/
err = ECHILD;
goto errout_with_errno;
}
-#endif
}
+#else
+ /* Check if the task has already died. Signals are not queued in
+ * NuttX. So a possibility is that the child has died and we
+ * missed the death of child signal (we got some other signal
+ * instead).
+ */
+
+ if (rtcb->nchildren == 0 ||
+ (pid != (pid_t)-1 && (ret = kill(pid, 0)) < 0))
+ {
+ /* We know that the child task was running okay we stared,
+ * so we must have lost the signal. What can we do?
+ * Let's claim we were interrupted by a signal.
+ */
+
+ err = EINTR;
+ goto errout_with_errno;
+ }
+#endif
/* Wait for any death-of-child signal */
@@ -447,7 +486,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
/* Yes... return the status and PID (in the event it was -1) */
- *stat_loc = info.si_status;
+ *stat_loc = info.si_status << 8;
pid = info.si_pid;
break;
}
diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c
index 708667993..5c00179dc 100644
--- a/nuttx/sched/sig_action.c
+++ b/nuttx/sched/sig_action.c
@@ -46,6 +46,7 @@
#include <errno.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "sig_internal.h"
/****************************************************************************
@@ -169,7 +170,6 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
FAR sigactq_t *sigact;
- int ret;
/* Since sigactions can only be installed from the running thread of
* execution, no special precautions should be necessary.
@@ -238,11 +238,11 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
/* Mark that status should be not be retained */
- rtcb->flags |= TCB_FLAG_NOCLDWAIT;
+ rtcb->group->tg_flags |= GROUP_FLAG_NOCLDWAIT;
/* Free all pending exit status */
- task_removechildren(rtcb);
+ group_removechildren(rtcb->group);
irqrestore(flags);
}
#endif
@@ -251,24 +251,31 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
if (act->sa_u._sa_handler == SIG_IGN)
{
- /* If there is a old sigaction, remove it from sigactionq */
+ /* Do we still have a sigaction container from the previous setting? */
- sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
+ if (sigact)
+ {
+ /* Yes.. Remove it from sigactionq */
+
+ sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
- /* And deallocate it */
+ /* And deallocate it */
- sig_releaseaction(sigact);
+ sig_releaseaction(sigact);
+ }
}
/* A sigaction has been supplied */
else
{
- /* Check if a sigaction was found */
+ /* Do we still have a sigaction container from the previous setting?
+ * If so, then re-use for the new signal action.
+ */
if (!sigact)
{
- /* No sigaction was found, but one is needed. Allocate one. */
+ /* No.. Then we need to allocate one for the new action. */
sigact = sig_allocateaction();
@@ -294,7 +301,7 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
COPY_SIGACTION(&sigact->act, act);
}
- return ret;
+ return OK;
}
/****************************************************************************
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 2ed929ab0..944743200 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -48,7 +48,7 @@
#include <nuttx/kmalloc.h>
#include "os_internal.h"
-#include "env_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Definitions
@@ -108,6 +108,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
{
FAR _TCB *tcb;
pid_t pid;
+ int errcode;
int ret;
/* Allocate a TCB for the new task. */
@@ -115,29 +116,39 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
tcb = (FAR _TCB*)kzalloc(sizeof(_TCB));
if (!tcb)
{
+ errcode = ENOMEM;
goto errout;
}
+ /* Allocate a new task group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_allocate(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_tcb;
+ }
+#endif
+
/* Associate file descriptors with the new task */
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- ret = sched_setuptaskfiles(tcb);
+ ret = group_setuptaskfiles(tcb);
if (ret != OK)
{
+ errcode = -ret;
goto errout_with_tcb;
}
#endif
- /* Clone the parent's task environment */
-
- (void)env_dup(tcb);
-
/* Allocate the stack for the TCB */
#ifndef CONFIG_CUSTOM_STACK
ret = up_create_stack(tcb, stack_size);
if (ret != OK)
{
+ errcode = -ret;
goto errout_with_tcb;
}
#endif
@@ -145,8 +156,9 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
/* Initialize the task control block */
ret = task_schedsetup(tcb, priority, task_start, entry, ttype);
- if (ret != OK)
+ if (ret < OK)
{
+ errcode = -ret;
goto errout_with_tcb;
}
@@ -154,6 +166,17 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
(void)task_argsetup(tcb, name, argv);
+ /* Now we have enough in place that we can join the group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_initialize(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_tcb;
+ }
+#endif
+
/* Get the assigned pid before we start the task */
pid = (int)tcb->pid;
@@ -163,6 +186,8 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
ret = task_activate(tcb);
if (ret != OK)
{
+ errcode = get_errno();
+
/* The TCB was added to the active task list by task_schedsetup() */
dq_rem((FAR dq_entry_t*)tcb, (dq_queue_t*)&g_inactivetasks);
@@ -175,7 +200,7 @@ errout_with_tcb:
sched_releasetcb(tcb);
errout:
- errno = ENOMEM;
+ set_errno(errcode);
return ERROR;
}
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 1813c12ed..889df25e0 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -49,6 +49,7 @@
#include <nuttx/fs/fs.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "sig_internal.h"
/****************************************************************************
@@ -103,10 +104,7 @@ static inline void task_atexit(FAR _TCB *tcb)
(*tcb->atexitfunc[index])();
- /* Nullify the atexit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the atext function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the atexit function to prevent its reuse. */
tcb->atexitfunc[index] = NULL;
}
@@ -119,10 +117,7 @@ static inline void task_atexit(FAR _TCB *tcb)
(*tcb->atexitfunc)();
- /* Nullify the atexit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the atext function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the atexit function to prevent its reuse. */
tcb->atexitfunc = NULL;
}
@@ -160,10 +155,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
(*tcb->onexitfunc[index])(status, tcb->onexitarg[index]);
- /* Nullify the on_exit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the atext function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the on_exit function to prevent its reuse. */
tcb->onexitfunc[index] = NULL;
}
@@ -175,10 +167,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
(*tcb->onexitfunc)(status, tcb->onexitarg);
- /* Nullify the on_exit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the on_exit function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the on_exit function to prevent its reuse. */
tcb->onexitfunc = NULL;
}
@@ -189,6 +178,89 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
#endif
/****************************************************************************
+ * Name: task_exitstatus
+ *
+ * Description:
+ * Report exit status when main task of a task group exits
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+static inline void task_exitstatus(FAR struct task_group_s *group, int status)
+{
+ FAR struct child_status_s *child;
+
+ /* Check if the parent task group has suppressed retention of
+ * child exit status information.
+ */
+
+ if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Find the exit status entry for this task in the parent TCB */
+
+ child = group_findchild(group, getpid());
+ DEBUGASSERT(child);
+ if (child)
+ {
+#ifndef HAVE_GROUP_MEMBERS
+ /* No group members? Save the exit status */
+
+ child->ch_status = status;
+#endif
+ /* Save the exit status.. For the case of HAVE_GROUP_MEMBERS,
+ * the child status will be as exited until the last member
+ * of the task group exits.
+ */
+
+ child->ch_status = status;
+ }
+ }
+}
+#else
+
+# define task_exitstatus(group,status)
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+
+/****************************************************************************
+ * Name: task_groupexit
+ *
+ * Description:
+ * Mark that the final thread of a child task group as exited.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+static inline void task_groupexit(FAR struct task_group_s *group)
+{
+ FAR struct child_status_s *child;
+
+ /* Check if the parent task group has suppressed retention of child exit
+ * status information.
+ */
+
+ if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Find the exit status entry for this task in the parent TCB */
+
+ child = group_findchild(group, getpid());
+ DEBUGASSERT(child);
+ if (child)
+ {
+ /* Mark that all members of the child task group has exit'ed */
+
+ child->ch_flags |= CHILD_FLAG_EXITED;
+ }
+ }
+}
+
+#else
+
+# define task_groupexit(group)
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+
+/****************************************************************************
* Name: task_sigchild
*
* Description:
@@ -197,72 +269,96 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
****************************************************************************/
#ifdef CONFIG_SCHED_HAVE_PARENT
-static inline void task_sigchild(FAR _TCB *tcb, int status)
+#ifdef HAVE_GROUP_MEMBERS
+static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status)
{
- FAR _TCB *ptcb;
+ FAR struct task_group_s *chgrp = ctcb->group;
+ FAR struct task_group_s *pgrp;
siginfo_t info;
- /* Only exiting tasks should generate SIGCHLD. pthreads use other
- * mechansims.
+ DEBUGASSERT(chgrp);
+
+ /* Get the parent task group. It is possible that all of the members of
+ * the parent task group have exited. This would not be an error. In
+ * this case, the child task group has been orphaned.
*/
- if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
+ pgrp = group_find(chgrp->tg_pgid);
+ if (!pgrp)
{
- /* Keep things stationary through the following */
+ /* Set the task group ID to an invalid group ID. The dead parent
+ * task group ID could get reused some time in the future.
+ */
- sched_lock();
+ chgrp->tg_pgid = INVALID_GROUP_ID;
+ return;
+ }
- /* Get the TCB of the receiving task */
+ /* Save the exit status now if this is the main thread of the task group
+ * that is exiting. Only the exiting main task of a task group carries
+ * interpretable exit Check if this is the main task that is exiting.
+ */
- ptcb = sched_gettcb(tcb->parent);
- if (!ptcb)
- {
- /* The parent no longer exists... bail */
+ if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
+ {
+ task_exitstatus(pgrp, status);
+ }
- sched_unlock();
- return;
- }
+ /* But only the final exiting thread in a task group, whatever it is,
+ * should generate SIGCHLD.
+ */
-#ifdef CONFIG_SCHED_CHILD_STATUS
- /* Check if the parent task has suppressed retention of child exit
- * status information. Only 'tasks' report exit status, not pthreads.
- * pthreads have a different mechanism.
+ if (chgrp->tg_nmembers == 1)
+ {
+ /* Mark that all of the threads in the task group have exited */
+
+ task_groupexit(pgrp);
+
+ /* Create the siginfo structure. We don't actually know the cause.
+ * That is a bug. Let's just say that the child task just exit-ted
+ * for now.
*/
- if ((ptcb->flags & TCB_FLAG_NOCLDWAIT) == 0)
- {
- FAR struct child_status_s *child;
+ info.si_signo = SIGCHLD;
+ info.si_code = CLD_EXITED;
+ info.si_value.sival_ptr = NULL;
+ info.si_pid = ctcb->pid;
+ info.si_status = status;
+
+ /* Send the signal. We need to use this internal interface so that we
+ * can provide the correct si_code value with the signal.
+ */
- /* No.. Find the exit status entry for this task in the parent TCB */
+ (void)group_signal(pgrp, &info);
+ }
+}
- child = task_findchild(ptcb, getpid());
- DEBUGASSERT(child);
- if (child)
- {
- /* Mark that the child has exit'ed */
+#else /* HAVE_GROUP_MEMBERS */
- child->ch_flags |= CHILD_FLAG_EXITED;
+static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status)
+{
+ siginfo_t info;
- /* Save the exit status */
+ /* If task groups are not supported then we will report SIGCHLD when the
+ * task exits. Unfortunately, there could still be threads in the group
+ * that are still running.
+ */
+
+ if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
+ {
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ /* Save the exit status now of the main thread */
+
+ task_exitstatus(ptcb->group, status);
+
+#else /* CONFIG_SCHED_CHILD_STATUS */
- child->ch_status = status;
- }
- }
-#else
/* Decrement the number of children from this parent */
DEBUGASSERT(ptcb->nchildren > 0);
ptcb->nchildren--;
-#endif
- /* Set the parent to an impossible PID. We do this because under
- * certain conditions, task_exithook() can be called multiple times.
- * If this function is called again, sched_gettcb() will fail on the
- * invalid parent PID above, nchildren will be decremented once and
- * all will be well.
- */
-
- tcb->parent = INVALID_PROCESS_ID;
+#endif /* CONFIG_SCHED_CHILD_STATUS */
/* Create the siginfo structure. We don't actually know the cause.
* That is a bug. Let's just say that the child task just exit-ted
@@ -272,7 +368,7 @@ static inline void task_sigchild(FAR _TCB *tcb, int status)
info.si_signo = SIGCHLD;
info.si_code = CLD_EXITED;
info.si_value.sival_ptr = NULL;
- info.si_pid = tcb->pid;
+ info.si_pid = ctcb->pid;
info.si_status = status;
/* Send the signal. We need to use this internal interface so that we
@@ -280,11 +376,72 @@ static inline void task_sigchild(FAR _TCB *tcb, int status)
*/
(void)sig_received(ptcb, &info);
+ }
+}
+
+#endif /* HAVE_GROUP_MEMBERS */
+#else /* CONFIG_SCHED_HAVE_PARENT */
+
+# define task_sigchild(x,ctcb,status)
+
+#endif /* CONFIG_SCHED_HAVE_PARENT */
+
+/****************************************************************************
+ * Name: task_leavegroup
+ *
+ * Description:
+ * Send the SIGCHILD signal to the parent thread
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_HAVE_PARENT
+static inline void task_leavegroup(FAR _TCB *ctcb, int status)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ DEBUGASSERT(ctcb && ctcb->group);
+
+ /* Keep things stationary throughout the following */
+
+ sched_lock();
+
+ /* Send SIGCHLD to all members of the parent's task group */
+
+ task_sigchild(ctcb->group->tg_pgid, ctcb, status);
+ sched_unlock();
+#else
+ FAR _TCB *ptcb;
+
+ /* Keep things stationary throughout the following */
+
+ sched_lock();
+
+ /* Get the TCB of the receiving, parent task. We do this early to
+ * handle multiple calls to task_leavegroup. ctcb->ppid is set to an
+ * invalid value below and the following call will fail if we are
+ * called again.
+ */
+
+ ptcb = sched_gettcb(ctcb->ppid);
+ if (!ptcb)
+ {
+ /* The parent no longer exists... bail */
+
sched_unlock();
+ return;
}
+
+ /* Send SIGCHLD to all members of the parent's task group */
+
+ task_sigchild(ptcb, ctcb, status);
+
+ /* Forget who our parent was */
+
+ ctcb->ppid = INVALID_PROCESS_ID;
+ sched_unlock();
+#endif
}
#else
-# define task_sigchild(tcb,status)
+# define task_leavegroup(ctcb,status)
#endif
/****************************************************************************
@@ -352,6 +509,16 @@ static inline void task_exitwakeup(FAR _TCB *tcb, int status)
void task_exithook(FAR _TCB *tcb, int status)
{
+ /* Under certain conditions, task_exithook() can be called multiple times.
+ * A bit in the TCB was set the first time this function was called. If
+ * that bit is set, then just ext doing nothing more..
+ */
+
+ if ((tcb->flags & TCB_FLAG_EXIT_PROCESSING) != 0)
+ {
+ return;
+ }
+
/* If exit function(s) were registered, call them now before we do any un-
* initialization. NOTE: In the case of task_delete(), the exit function
* will *not* be called on the thread execution of the task being deleted!
@@ -363,9 +530,9 @@ void task_exithook(FAR _TCB *tcb, int status)
task_onexit(tcb, status);
- /* Send SIGCHLD to the parent of the exit-ing task */
+ /* Leave the task group */
- task_sigchild(tcb, status);
+ task_leavegroup(tcb, status);
/* Wakeup any tasks waiting for this task to exit */
@@ -376,26 +543,27 @@ void task_exithook(FAR _TCB *tcb, int status)
*/
#if CONFIG_NFILE_STREAMS > 0
- (void)lib_flushall(tcb->streams);
+ (void)lib_flushall(&tcb->group->tg_streamlist);
#endif
- /* Discard any un-reaped child status (no zombies here!) */
+ /* Leave the task group. Perhaps discarding any un-reaped child
+ * status (no zombies here!)
+ */
-#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
- task_removechildren(tcb);
+#ifdef HAVE_TASK_GROUP
+ group_leave(tcb);
#endif
- /* Free all file-related resources now. This gets called again
- * just be be certain when the TCB is delallocated. However, we
- * really need to close files as soon as possible while we still
- * have a functioning task.
- */
-
- (void)sched_releasefiles(tcb);
-
/* Deallocate anything left in the TCB's queues */
#ifndef CONFIG_DISABLE_SIGNALS
sig_cleanup(tcb); /* Deallocate Signal lists */
#endif
+
+ /* This function can be re-entered in certain cases. Set a flag
+ * bit in the TCB to not that we have already completed this exit
+ * processing.
+ */
+
+ tcb->flags |= TCB_FLAG_EXIT_PROCESSING;
}
diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c
index 0f0fdc68e..78f35bc2a 100644
--- a/nuttx/sched/task_init.c
+++ b/nuttx/sched/task_init.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/task_init.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -42,10 +42,12 @@
#include <sys/types.h>
#include <stdint.h>
#include <sched.h>
+#include <errno.h>
+
#include <nuttx/arch.h>
#include "os_internal.h"
-#include "env_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Definitions
@@ -102,10 +104,10 @@
* parameters are required, argv may be NULL.
*
* Return Value:
- * OK on success; ERROR on failure. (See task_schedsetup() for possible
- * failure conditions). On failure, the caller is responsible for freeing
- * the stack memory and for calling sched_releasetcb() to free the TCB
- * (which could be in most any state).
+ * OK on success; ERROR on failure with errno set appropriately. (See
+ * task_schedsetup() for possible failure conditions). On failure, the
+ * caller is responsible for freeing the stack memory and for calling
+ * sched_releasetcb() to free the TCB (which could be in most any state).
*
****************************************************************************/
@@ -118,20 +120,30 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
main_t entry, const char *argv[])
#endif
{
+ int errcode;
int ret;
- /* Associate file descriptors with the new task */
+ /* Create a new task group */
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- if (sched_setuptaskfiles(tcb) != OK)
+#ifdef HAVE_TASK_GROUP
+ ret = group_allocate(tcb);
+ if (ret < 0)
{
- return ERROR;
+ errcode = -ret;
+ goto errout;
}
#endif
- /* Clone the parent's task environment */
+ /* Associate file descriptors with the new task */
- (void)env_dup(tcb);
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+ ret = group_setuptaskfiles(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_group;
+ }
+#endif
/* Configure the user provided stack region */
@@ -143,13 +155,35 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
ret = task_schedsetup(tcb, priority, task_start, entry,
TCB_FLAG_TTYPE_TASK);
- if (ret == OK)
+ if (ret < OK)
{
- /* Setup to pass parameters to the new task */
+ errcode = -ret;
+ goto errout_with_group;
+ }
+
+ /* Setup to pass parameters to the new task */
+
+ (void)task_argsetup(tcb, name, argv);
+
+ /* Now we have enough in place that we can join the group */
- (void)task_argsetup(tcb, name, argv);
+#ifdef HAVE_TASK_GROUP
+ ret = group_initialize(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_group;
}
+#endif
+ return OK;
- return ret;
+errout_with_group:
+#ifdef HAVE_TASK_GROUP
+ group_leave(tcb);
+
+errout:
+#endif
+ set_errno(errcode);
+ return ERROR;
}
diff --git a/nuttx/sched/task_posixspawn.c b/nuttx/sched/task_posixspawn.c
index 7bb9c9a4d..e9ad1fc45 100644
--- a/nuttx/sched/task_posixspawn.c
+++ b/nuttx/sched/task_posixspawn.c
@@ -54,6 +54,7 @@
#include <nuttx/spawn.h>
#include "os_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Private Types
diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c
index 28d371bf1..5bb62893f 100644
--- a/nuttx/sched/task_reparent.c
+++ b/nuttx/sched/task_reparent.c
@@ -42,6 +42,7 @@
#include <errno.h>
#include "os_internal.h"
+#include "group_internal.h"
#ifdef CONFIG_SCHED_HAVE_PARENT
@@ -69,6 +70,141 @@
*
*****************************************************************************/
+#ifdef HAVE_GROUP_MEMBERS
+int task_reparent(pid_t ppid, pid_t chpid)
+{
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ FAR struct child_status_s *child;
+#endif
+ FAR struct task_group_s *chgrp;
+ FAR struct task_group_s *ogrp;
+ FAR struct task_group_s *pgrp;
+ _TCB *tcb;
+ gid_t ogid;
+ gid_t pgid;
+ irqstate_t flags;
+ int ret;
+
+ /* Disable interrupts so that nothing can change in the relatinoship of
+ * the three task: Child, current parent, and new parent.
+ */
+
+ flags = irqsave();
+
+ /* Get the child tasks task group */
+
+ tcb = sched_gettcb(chpid);
+ if (!tcb)
+ {
+ ret = -ECHILD;
+ goto errout_with_ints;
+ }
+
+ DEBUGASSERT(tcb->group);
+ chgrp = tcb->group;
+
+ /* Get the GID of the old parent task's task group (ogid) */
+
+ ogid = chgrp->tg_pgid;
+
+ /* Get the old parent task's task group (ogrp) */
+
+ ogrp = group_find(ogid);
+ if (!ogrp)
+ {
+ ret = -ESRCH;
+ goto errout_with_ints;
+ }
+
+ /* If new parent task's PID (ppid) is zero, then new parent is the
+ * grandparent will be the new parent, i.e., the parent of the current
+ * parent task.
+ */
+
+ if (ppid == 0)
+ {
+ /* Get the grandparent task's task group (pgrp) */
+
+ pgid = ogrp->tg_pgid;
+ pgrp = group_find(pgid);
+ }
+ else
+ {
+ /* Get the new parent task's task group (pgrp) */
+
+ tcb = sched_gettcb(ppid);
+ if (!tcb)
+ {
+ ret = -ESRCH;
+ goto errout_with_ints;
+ }
+
+ pgrp = tcb->group;
+ pgid = pgrp->tg_gid;
+ }
+
+ if (!pgrp)
+ {
+ ret = -ESRCH;
+ goto errout_with_ints;
+ }
+
+ /* Then reparent the child. Notice that we don't actually change the
+ * parent of the task. Rather, we change the parent task group for
+ * all members of the child's task group.
+ */
+
+ chgrp->tg_pgid = pgid;
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ /* Remove the child status entry from old parent task group */
+
+ child = group_removechild(ogrp, chpid);
+ if (child)
+ {
+ /* Has the new parent's task group supressed child exit status? */
+
+ if ((pgrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Add the child status entry to the new parent's task group */
+
+ group_addchild(pgrp, child);
+ }
+ else
+ {
+ /* Yes.. Discard the child status entry */
+
+ group_freechild(child);
+ }
+
+ /* Either case is a success */
+
+ ret = OK;
+ }
+ else
+ {
+ /* This would not be an error if the original parent's task group has
+ * suppressed child exit status.
+ */
+
+ ret = ((ogrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
+ }
+
+#else /* CONFIG_SCHED_CHILD_STATUS */
+
+ DEBUGASSERT(otcb->nchildren > 0);
+
+ otcb->nchildren--; /* The orignal parent now has one few children */
+ ptcb->nchildren++; /* The new parent has one additional child */
+ ret = OK;
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+
+errout_with_ints:
+ irqrestore(flags);
+ return ret;
+}
+#else
int task_reparent(pid_t ppid, pid_t chpid)
{
#ifdef CONFIG_SCHED_CHILD_STATUS
@@ -98,7 +234,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
/* Get the PID of the child task's parent (opid) */
- opid = chtcb->parent;
+ opid = chtcb->ppid;
/* Get the TCB of the child task's parent (otcb) */
@@ -116,7 +252,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
if (ppid == 0)
{
- ppid = otcb->parent;
+ ppid = otcb->ppid;
}
/* Get the new parent task's TCB (ptcb) */
@@ -130,34 +266,55 @@ int task_reparent(pid_t ppid, pid_t chpid)
/* Then reparent the child */
- chtcb->parent = ppid; /* The task specified by ppid is the new parent */
+ chtcb->ppid = ppid; /* The task specified by ppid is the new parent */
#ifdef CONFIG_SCHED_CHILD_STATUS
/* Remove the child status entry from old parent TCB */
- child = task_removechild(otcb, chpid);
+ child = group_removechild(otcb->group, chpid);
if (child)
{
- /* Add the child status entry to the new parent TCB */
+ /* Has the new parent's task group supressed child exit status? */
+
+ if ((ptcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Add the child status entry to the new parent's task group */
+
+ group_addchild(ptcb->group, child);
+ }
+ else
+ {
+ /* Yes.. Discard the child status entry */
+
+ group_freechild(child);
+ }
+
+ /* Either case is a success */
- task_addchild(ptcb, child);
ret = OK;
}
else
{
- ret = -ENOENT;
+ /* This would not be an error if the original parent's task group has
+ * suppressed child exit status.
+ */
+
+ ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
}
-#else
+
+#else /* CONFIG_SCHED_CHILD_STATUS */
+
DEBUGASSERT(otcb->nchildren > 0);
otcb->nchildren--; /* The orignal parent now has one few children */
ptcb->nchildren++; /* The new parent has one additional child */
ret = OK;
-#endif
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
errout_with_ints:
irqrestore(flags);
return ret;
}
-
+#endif
#endif /* CONFIG_SCHED_HAVE_PARENT */
diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c
index 43ed24b32..b770d46e6 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/task_setup.c
*
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,6 +49,7 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Definitions
@@ -150,7 +151,8 @@ static int task_assignpid(FAR _TCB *tcb)
* Name: task_saveparent
*
* Description:
- * Save the task ID of the parent task in the child task's TCB.
+ * Save the task ID of the parent task in the child task's TCB and allocate
+ * a child status structure to catch the child task's exit status.
*
* Parameters:
* tcb - The TCB of the new, child task.
@@ -170,31 +172,57 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+#if defined(HAVE_GROUP_MEMBERS) || defined(CONFIG_SCHED_CHILD_STATUS)
+ DEBUGASSERT(tcb && tcb->group && rtcb->group);
+#else
+#endif
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Save the ID of the parent tasks' task group in the child's task group.
+ * Do nothing for pthreads. The parent and the child are both members of
+ * the same task group.
+ */
+
+ if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD)
+ {
+ /* This is a new task in a new task group, we have to copy the ID from
+ * the parent's task group structure to child's task group.
+ */
+
+ tcb->group->tg_pgid = rtcb->group->tg_gid;
+ }
+
+#else
+ DEBUGASSERT(tcb);
+
/* Save the parent task's ID in the child task's TCB. I am not sure if
* this makes sense for the case of pthreads or not, but I don't think it
* is harmful in any event.
*/
- tcb->parent = rtcb->pid;
+ tcb->ppid = rtcb->pid;
+#endif
- /* Exit status only needs to be retained for the case of tasks, however */
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ /* Tasks can also suppress retention of their child status by applying
+ * the SA_NOCLDWAIT flag with sigaction().
+ */
- if (ttype == TCB_FLAG_TTYPE_TASK)
+ if ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
{
-#ifdef CONFIG_SCHED_CHILD_STATUS
FAR struct child_status_s *child;
/* Make sure that there is not already a structure for this PID in the
* parent TCB. There should not be.
*/
- child = task_findchild(rtcb, tcb->pid);
+ child = group_findchild(rtcb->group, tcb->pid);
DEBUGASSERT(!child);
if (!child)
{
/* Allocate a new status structure */
- child = task_allocchild();
+ child = group_allocchild();
}
/* Did we successfully find/allocate the child status structure? */
@@ -210,16 +238,16 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype)
/* Add the entry into the TCB list of children */
- task_addchild(rtcb, child);
+ group_addchild(rtcb->group, child);
}
+ }
#else
- DEBUGASSERT(rtcb->nchildren < UINT16_MAX);
- rtcb->nchildren++;
+ DEBUGASSERT(rtcb->nchildren < UINT16_MAX);
+ rtcb->nchildren++;
#endif
- }
}
#else
-# define task_saveparent(tcb, type)
+# define task_saveparent(tcb,ttype)
#endif
/****************************************************************************
@@ -318,7 +346,9 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main,
tcb->flags &= ~TCB_FLAG_TTYPE_MASK;
tcb->flags |= ttype;
- /* Save the task ID of the parent task in the TCB */
+ /* Save the task ID of the parent task in the TCB and allocate
+ * a child status structure.
+ */
task_saveparent(tcb, ttype);
diff --git a/nuttx/sched/task_start.c b/nuttx/sched/task_start.c
index a9cc38dfc..5a32a5dd8 100644
--- a/nuttx/sched/task_start.c
+++ b/nuttx/sched/task_start.c
@@ -94,6 +94,15 @@ void task_start(void)
FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
int argc;
+ /* Execute the start hook if one has been registered */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+ if (tcb->starthook)
+ {
+ tcb->starthook(tcb->starthookarg);
+ }
+#endif
+
/* Count how many non-null arguments we are passing */
for (argc = 1; argc <= CONFIG_MAX_TASK_ARGS; argc++)
diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/task_starthook.c
index a3ef71af4..1cb29349f 100644
--- a/nuttx/sched/sched_releasefiles.c
+++ b/nuttx/sched/task_starthook.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sched_releasefiles.c
+ * sched/task_start.c
*
- * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,12 +39,29 @@
#include <nuttx/config.h>
-#include <sched.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/net/net.h>
-#include <nuttx/lib.h>
+#include <nuttx/sched.h>
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+#ifdef CONFIG_SCHED_STARTHOOK
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
/****************************************************************************
* Private Functions
@@ -55,60 +72,29 @@
****************************************************************************/
/****************************************************************************
- * Name: sched_releasefiles
+ * Name: task_starthook
*
* Description:
- * Release file resources attached to a TCB. This file may be called
- * multiple times as a task exists. It will be called as early as possible
- * to support proper closing of complex drivers that may need to wait
- * on external events.
+ * Configure a start hook... a function that will be called on the thread
+ * of the new task before the new task's main entry point is called.
+ * The start hook is useful, for example, for setting up automatic
+ * configuration of C++ constructors.
*
- * Parameters:
- * tcb - tcb of the new task.
+ * Inputs:
+ * tcb - The new, unstarted task task that needs the start hook
+ * starthook - The pointer to the start hook function
+ * arg - The argument to pass to the start hook function.
*
- * Return Value:
+ * Return:
* None
*
- * Assumptions:
- *
****************************************************************************/
-int sched_releasefiles(_TCB *tcb)
+void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg)
{
- if (tcb)
- {
-#if CONFIG_NFILE_DESCRIPTORS > 0
- /* Free the file descriptor list */
-
- if (tcb->filelist)
- {
- files_releaselist(tcb->filelist);
- tcb->filelist = NULL;
- }
-
-#if CONFIG_NFILE_STREAMS > 0
- /* Free the stream list */
-
- if (tcb->streams)
- {
- lib_releaselist(tcb->streams);
- tcb->streams = NULL;
- }
-#endif /* CONFIG_NFILE_STREAMS */
-#endif /* CONFIG_NFILE_DESCRIPTORS */
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- /* Free the file descriptor list */
-
- if (tcb->sockets)
- {
- net_releaselist(tcb->sockets);
- tcb->sockets = NULL;
- }
-#endif /* CONFIG_NSOCKET_DESCRIPTORS */
- }
-
- return OK;
+ DEBUGASSERT(tcb);
+ tcb->starthook = starthook;
+ tcb->starthookarg = arg;
}
-#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
+#endif /* CONFIG_SCHED_STARTHOOK */
diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c
index fece4c596..ac86ddc56 100644
--- a/nuttx/sched/task_vfork.c
+++ b/nuttx/sched/task_vfork.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
+#include <sys/wait.h>
#include <stdint.h>
#include <assert.h>
#include <queue.h>
@@ -48,7 +49,7 @@
#include <nuttx/sched.h>
#include "os_internal.h"
-#include "env_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Pre-processor Definitions
@@ -125,17 +126,13 @@ FAR _TCB *task_vforksetup(start_t retaddr)
/* Associate file descriptors with the new task */
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- ret = sched_setuptaskfiles(child);
+ ret = group_setuptaskfiles(child);
if (ret != OK)
{
goto errout_with_tcb;
}
#endif
- /* Clone the parent's task environment */
-
- (void)env_dup(child);
-
/* Get the priority of the parent task */
#ifdef CONFIG_PRIORITY_INHERITANCE
diff --git a/nuttx/sched/timer_initialize.c b/nuttx/sched/timer_initialize.c
index 05980bb1a..2651469ef 100644
--- a/nuttx/sched/timer_initialize.c
+++ b/nuttx/sched/timer_initialize.c
@@ -137,7 +137,7 @@ void weak_function timer_initialize(void)
* resources are referenced.
*
* Parameters:
- * pid - the task ID of the thread that exitted
+ * pid - the task ID of the thread that exited
*
* Return Value:
* None
diff --git a/nuttx/tools/mkconfig.c b/nuttx/tools/mkconfig.c
index d8d09df34..a622743a0 100644
--- a/nuttx/tools/mkconfig.c
+++ b/nuttx/tools/mkconfig.c
@@ -126,17 +126,23 @@ int main(int argc, char **argv, char **envp)
printf("#ifndef CONFIG_RR_INTERVAL\n");
printf("# define CONFIG_RR_INTERVAL 0\n");
printf("#endif\n\n");
- printf("/* The correct way to disable filesystem supuport is to set the\n");
- printf(" * number of file descriptors to zero.\n");
+ printf("/* The correct way to disable filesystem supuport is to set the number of\n");
+ printf(" * file descriptors to zero.\n");
printf(" */\n\n");
printf("#ifndef CONFIG_NFILE_DESCRIPTORS\n");
printf("# define CONFIG_NFILE_DESCRIPTORS 0\n");
printf("#endif\n\n");
- printf("/* If a console is selected, then make sure that there are\n");
- printf(" * resources for 3 file descriptors and, if any streams are\n");
- printf(" * selected, also for 3 file streams.\n");
+ printf("/* If a console is selected, then make sure that there are resources for\n");
+ printf(" * three file descriptors and, if any streams are selected, also for three\n");
+ printf(" * file streams.\n");
+ printf(" *\n");
+ printf(" * CONFIG_DEV_CONSOLE means that a builtin console device exists at /dev/console\n");
+ printf(" * and can be opened during boot-up. Other consoles, such as USB consoles, may\n");
+ printf(" * not exist at boot-upand have to be handled in a different way. Three file\n");
+ printf(" * descriptors and three file streams are still needed.\n");
printf(" */\n\n");
- printf("#ifdef CONFIG_DEV_CONSOLE\n");
+ printf("#if defined(CONFIG_DEV_CONSOLE) || defined(CONFIG_CDCACM_CONSOLE) || \\\n");
+ printf(" defined(CONFIG_PL2303_CONSOLE)\n");
printf("# if CONFIG_NFILE_DESCRIPTORS < 3\n");
printf("# undef CONFIG_NFILE_DESCRIPTORS\n");
printf("# define CONFIG_NFILE_DESCRIPTORS 3\n");
@@ -145,12 +151,10 @@ int main(int argc, char **argv, char **envp)
printf("# undef CONFIG_NFILE_STREAMS\n");
printf("# define CONFIG_NFILE_STREAMS 3\n");
printf("# endif\n\n");
- printf("/* If no console is selected, then disable all console devices */\n\n");
+ printf("/* If no console is selected, then disable all builtin console devices */\n\n");
printf("#else\n");
printf("# undef CONFIG_DEV_LOWCONSOLE\n");
printf("# undef CONFIG_RAMLOG_CONSOLE\n");
- printf("# undef CONFIG_CDCACM_CONSOLE\n");
- printf("# undef CONFIG_PL2303_CONSOLE\n");
printf("#endif\n\n");
printf("/* If priority inheritance is disabled, then do not allocate any\n");
printf(" * associated resources.\n");