The gpssim code was named gps_sim vs being consistent with other
simulators (gpssim). It also used warnx and errx and had lots of
commeted out code.
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
APU requires the use of ?= for MK_DIR but the use of lastword was
causing MK_DIR to be a subdir of makefiles. Changed lastword to
firstword (which is always the path to firmware.mk) which fixed
the problem.
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
Moved nuttx specific make rules to files in makefiles/nuttx.
All target specific makefiles are in their target sub directories.
To minimize file duplication, targets that share rules include a
common file. For example the posix and posix-arm targets both use
makefiles/posix/posix_elf.mk
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
Changed rc.S to rcS.
Updated README.md to explain the require directory structure and
where to run mainapp from for SITL to work correctly.
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
The SITL build is now the default posix build.
The linker script for posix was moved to makefiles/posix.
The rc.S file was moved to posix-configs/SITL/init/
The POSIXTEST board definition is now SITL
To run the SITL test run:
make sitlrun
This replaces the make posixrun target.
The build directory is now Build/posix_sitl.build/
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
before an advertiser for multi_pub/subs.
This is achieved using
- A "published" flag for each uORB device node
- A check before increasing the instance count (basically, a node is
re-used if nothing has been published on it before which means that it
has been created by a subscriber.
Since the PX4 code uses both px4_task and pthread APIs,
px4_getpid() must be save to call from either context.
On posix, this means we have to always return the pthread ID.
Reverted simulator change of pthread to px4_task
There may have been side effects if this was build for a target that
has process/task scoped file descriptors. It is now safe to call
px4_getpid() from this pthread context with this change for the
posix build for px4_getpid().
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
In nuttx the mode parameter to open is not required but in Linux,
and per the POSIX spec, mode is required if the O_CREAT flag is
passed.
The mode flags are different for NuttX and Linux so a new set of
PX4 defines was added:
PX4_O_MODE_777 - read, write, execute for user, group and other
PX4_O_MODE_666 - read, and write for user, group and other
PX4_O_MODE_600 - read, and write for user
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
mcu_unique_id() reads registers at an invalid address in non-nuttx builds.
Added ifdef to return a dummy value for non-nuttx builds.
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
The simulator was using pthread APIs directly so calls to px4_getpid()
would fail since the task ID was not known. Changed simulator to use
px4_task_spawn_cmd.
Signed-off-by: Mark Charlebois <charlebm@gmail.com>