- use a linked-list instead of std::vector. Insertion and removal are now
O(1)
- avoid malloc and use a thread_local instance of TimedWait.
It gets destroyed when the thread exits, so we have to add protection
in case a thread exits too quickly. This in turn requires a fix to the
unit-tests.
The API of cond_timedwait was wrong. It used return -1 and set errno
instead of returning the error as specified for pthread_cond_timedwait
which it tries to mock.
It seems that the hysteresis test fails every now and then, presumably
due to timing issues. The tests needs some improvements, e.g. isolating
it from the system time.
@bkueng found that the old implementation was likely to wrap-around
given seconds is only a uint32_t. We now cast it directly to uint64_t
and therefore should fix this problem.
This uses the "fake" px4_sem based on mutex and condition_variable on
all POSIX system, not just macOS and Cygwin. This means that we can
change px4_sem_timedwait under the hood and inject the simulated time.
This integrates the lockstep_scheduler, so that the system time is set
by the mavlink HIL_SENSOR message.
This means that the speed factor is removed and the speed is entirely
given by the simulator.
These contains some rough changes trying to get SITL to speed up by a
SPEED_FACTOR.
This platform time code probably requires some more thought and refactor
but this gets a demo at 4x working.
You can now add `DYNAMIC` as an option to `px4_add_module`, which will
cause that module to no longer be compiled into the px4 executable, but
instead produce a separate shared library file, which can be loaded and
executed with the new `dyn` command:
pxh> dyn ./hello.px4mod start
This will load the shared object file `hello.px4mod` if it wasn't
already loaded, and execute its main function with the given arguments.
The threads running commands for clients through the Posix daemon used
to write to a char buffer through snprintf (etc.) which was then written
directly to the file descriptor, whereas in the other case printf
(etc.) was used to write to stdout (FILE*). Both versions used some
macro's and repeated code to have the same output.
This change unifies these two cases by using a FILE* in both cases. The
(line) buffering is done by the standard C library's implementation
(just like with stdout), and px4_log.c now uses the same code in all
cases (using fprintf, etc.) for printing (colored) output.
Because it was always failing from the beginning on and
we want to make sure no other tests break in the meantime
by running the currently passing tests also on Windows CI.
Unlike pipes, unix sockets provide bi-directional
communication with each connected client.
- No need to generate a unique uuid per client anymore.
- The client doesn't have to create its own pipe anymore.
- Since there is no risk of multiple client's writes getting mixed up,
messages don't need to fit in a single write anymore, removing the
limit on command length.
- Since the server can detect a connection closing, the client no longer
needs to handle signals. When the client is killed, the connection is
automatically closed, which will cause the server to kill the related
px4 thread.
Since this does not rely on handling signals and the client sending an
additional message, this is much more reliable.
- Client is no longer a singleton.
- The protocol is simplified. Standard output is directly written to the
socket back to the client, without wrapping it in any protocol
message.
- Because of the simple protocol, one could now even use netcat to run a
px4 command:
$ echo hello | netcat -UN /tmp/px4-sock-0
Also removes a few race conditions.
Fixes these invalid format strings:
- A `%d` for a pointer (replaced it by `%p`)
- A 0x%08x (and a 0x%0x8!) for a pointer (replaced by %p)
- 2 cases of `%d` for a `ssize_t` (replaced it by `%zi`)
- 1 case of a %u for an `int` (replaced by %i)
- 3 cases of %d for a `long` (replaced by %ld)
- 19 cases of `%d`, `%i`, `%u` or `%lu` for a `size_t` (replaced it by `%zu`)
- An unused formatting argument (removed it)
- A missing `%d` (added it)
- A missing `%s` (added it)
- 2 cases of `%llu` for a `uint64_t` (replaced it by `"%" PRIu64`)
- 6 cases of giving a string directly as format string (replaced it by `("%s", string)`)
- 2 cases of %*-s, which should probably have been %-*s.
(Looks like NuttX accepts (the invalid) %*-s, but other platforms don't.)
- A %04x for a `uint32_t` (replaced by "%04" PRIx32)
This uses the systems default shell:
- Ubuntu: dash
- Fedora: bash
Since bash is invoked via /bin/sh, it operates in POSIX mode:
https://tiswww.case.edu/php/chet/bash/POSIX
- remove '# Ignore the expand_aliases command in zshell.'
Not needed because the shell operates in POSIX mode
- [[ is bashism -> use [
- autostart_files=( $autostart_file_match )
is not supported in dash, so use 'ls'
- shellcheck runs the dash flavor, since dash is a minimalistic shell.
Tested on dash & bash.
This insures the common exception handler will not be
re-entered. The handler does not support nested interrupts
and the interrupt stack pointer and context will be overwritten
resulting in hard to debug hardfaults.
If all the priorities are equal the NVIC prevents the
preemption. The startup code defaults all the priorities
to the same value 128.
This change safeguards in 2 ways 1) By disabling
CONFIG_ ARCH_IRQPRIO: up_prioritize_irq cannot be called.
This will insure that all HW interrupts are at the same
priority.
2) By disabling CONFIG_ARCH_HIPRI_INTERRUP, the common
exception will disable any interrupts during interrupt
processing.