By the time we create the storage we hadn't still initialized the
buffer. Remove the writes during storage creation since ftruncate() will
take care of the file size aspect and MAX storage write chunk is taken
care by Linux according to the media/fs that is there.
In some point in past it may have been ttyS2, but right now on kernel
4.16+ the UART is on ttyS5. We could do like is done for I2C and search
on sysfs, but it requires additional changes.
Apparently this code came in part from libuavcan that defines this
struct Control. They also had the same issue detailed on
https://github.com/UAVCAN/libuavcan/issues/116.
The solution here is much simpler though: stick to the design of cmsg()
even if it's C. As per cmsg(3), use a union together with CMSG_SPACE().
Use a const variable instead of a define so we don't polute the
environment with a define specific to this function.
Also remove tabs and replace with proper coding style.
This adds a counter here to only loop to a maximum number of iterations.
Now we avoid situations in which we would be stuck processing packets here.
This also adds some other meaningful defines
Removes compile-time selection of RCInput driver for ocpoc_zynq.
PPM and SBUS input are now colocated on the ocpoc board, and it
only needs to run RCInput_ZYNQ. Pulse input is also inverted
to accommodate SBUS input, which has no effect on PPM input.
On kernels 4.7+ duty_cycle should always be less than period.
Otherways, we'll get a EINVAL.
It makes sense to set duty_cycle to 0, as
duty_cycle doesn't really make sense without a proper period.
A proper way to handle these errors might be to call pwm_adjust_config
in every pwmchip backend but it's unrealistic to hope that all vendors
will do it quickly.
If we are the controlling terminal for a tty device we will receive a
SIGHUP when the device disappears. Currently what happens is that we
simply stop the whole process. We don't want to fall off the sky due
to a bad device. This can happen for any reason, but it's more likely
if the UART is behind a USB connection.
These messages are only valid in a small subset of Linux boards (those
based on BBB and variants). The ToneAlarm class should actually be
split allowing different implementations, but for now let's just disable
the message.
It's not being sold, there are just a few (different) engineering
samples built and there are no plans for this to go forward for people
that were pushing it.
There's an implicit (apart from the name) dependency between SPI and
SPIUARTDriver which results in a crush on a restart or a shutdown.
By moving the initialization we're making sure that all objects are
deleted in the right order.
_export_path and _duty_path will have been already long time gone by the
time dtors kick in.
Probably better to use OwnPtr around those. But it's better to be done
in a separate PR.
Checking the time on the tcpdump capture, it matches the first fields
from the data:
$ tshark -n -c 4 -r ~/tmp/solo/rc.pcap
1 0.000000 10.1.1.1 → 10.1.1.10 UDP 68 5005 → 5005 Len=26
2 0.019976 10.1.1.1 → 10.1.1.10 UDP 68 5005 → 5005 Len=26
3 0.040046 10.1.1.1 → 10.1.1.10 UDP 68 5005 → 5005 Len=26
4 0.059961 10.1.1.1 → 10.1.1.10 UDP 68 5005 → 5005 Len=26
From the previous commit (first 2 packets):
5fa8 f441 3414 0500 73d7 dc05 dc05 dc05 db05 e803 e803 e803 f401
73f6 f441 3414 0500 74d7 dc05 dc05 dc05 db05 e803 e803 e803 f401
0x0005143441f45fa8 - 0x0005143441f4f673 = 0x4E14 = 19988 (usec)
Which seems to approximately match for the other packets as well. We are
not using the field since we rather get the time when we receive it, but
at least use a better name.
If a thread other than the main one calls Scheduler::delay() we could
end up triggering the call of delay callbacks. Those should only ever
happen on the main thread.
We are setting a termination handler for some signals which are of not
interest. Just ignore them. Ignoring SIGWINCH allows for example to
run on a screen and change the window size later without killing
ardupilot.
RPI-based boards that use RCInput_RPI need more stack space otherwise we
end up with stack corruption. This leads to crash particularly when also
using GPIO_RPI since it may change what that driver is poking on memory.
This increases stack size to 1M which is overkill for most of other
boards with a more controllable stack usage. However this exposes that
on multiple different HWs a single point for stack size decision may not
be the best. This can be improved in future.
While at it, add final and override to mark this as being the overriden
final implementation of this method.
Thanks to Phillip Khandeliants (@khandeliants) for reporting.
While at it, add final and override to mark this as being the overriden
final implementation of this method.
Thanks to Phillip Khandeliants (@khandeliants) for reporting.
Integrate the gyro values pushed by the inertial sensor backend using
bias values sent by EKF.
Use the unblocking RingBuffer to avoid locking the callers.
- avoid trying to close fd when it's -1
- Keep includes sorted
- AP_HAL::panic() doesn't need \n terminator
- %u requires unsigned type
- #pragma once is the first thing on a header
when a library called read() it would clear the new input flag, which
would cause new_input() in the main loop to return false. This could
trigger a false RC failsafe.
When PWM_Sysfs_Base constructor is called, global variable hal may not
have been initialized resulting in NULL dereferencing error.
Move hal dependent stuff from contructor to init method.
By opening with O_CLOEXEC we make sure we don't leak the file descriptor
when we are exec'ing or calling out subprograms. Right now we currently
don't do it so there's no harm, but it's good practice in Linux to have
it.
Several return values in the constructor of the scheduler were ignored
before, while they should be respected.
I found that bug while strac'ing ardupilot as it failed at some later
point.
Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>
This allows to terminate the flight stack nicely, ensuring it returns 0
so init system can check by return code if it terminated nicely or if it
was due to a crash.
This allows to wakeup the thread that is sleeping on Poller::poll()
[ which in our case is an epoll_wait() call ]. This is usually achieved
by using a special signal and using the pwait() variant of the sleeping
function (or using signalfd). However integrating the signal in the
Thread class is more complex than simply use the eventfd syscall which
can serve our needs.
Up until now we rely on Thread objects and variants thereof to be allocated
on heap or embedded in another object that's zero'ed on initialization.
However sometimes it's convenient to be able to use them on stack as
will be the case when writting unit tests.
Initialize all relevant fields to allow them to be used on stack. While
at it, prefer C++11 initialization on Poller since it's only setting the
default (invalid) value.
RC_Channel: To nullptr from NULL.
AC_Fence: To nullptr from NULL.
AC_Avoidance: To nullptr from NULL.
AC_PrecLand: To nullptr from NULL.
DataFlash: To nullptr from NULL.
SITL: To nullptr from NULL.
GCS_MAVLink: To nullptr from NULL.
DataFlash: To nullptr from NULL.
AP_Compass: To nullptr from NULL.
Global: To nullptr from NULL.
Global: To nullptr from NULL.
This patch replaces the 'old style' ringbuffer by the ByteBuffer class.
An effort was made to keep the exchange as close as possible from a
drop-in replacement to minimize the risk of introducing bugs.
Although the exchange opens opportunities for improvement and
simplification of this class.
When the buffer wraps and we do it in 2 steps, we can't actually do the
second part if it fails or if we wrote less bytes than we intended,
otherwise we will corrupt the data being sent.
This patch replaces the 'old style' ringbuffer by the ByteBuffer class.
An effort was made to keep the exchange as close as possible from a
drop-in replacement to minimize the risk of introducing bugs.
Although the exchange opens opportunities for improvement and
simplification of this class.
The constant passed to cflag is BOTHER, meaning the actual baud is set
in the other specific members. Don't define B* constants as they are
misleading here and this is why it doesn't work with e.g.
cfset[io]speed()... that function expect a B* constant which in Linux
is not the speed, but an index to an array with speeds.
Accidentally pushed in commit 298f7bffb9
The order of the motors shouldn't have been changed on version 5 because
it is specific to older versions of the ESC controller firmware
We currently check examples are buildable with waf which doesn't need
the libraries to be specified in a make.inc file. Having the makefiles
there is misleading since people try to build and realize the build is
broken.
this is a RCInput module for multiple R/C uart protocols running at
115200 baud 8-bit. We can decode multiple protocols in parallel with
this module, relying on frame timing and CRCs to get the right
protocol
Contributions from:
- Gustavo Jose de Sousa <gustavo.sousa@intel.com>
- José Roberto de Souza <jose.souza@intel.com>
- Lucas De Marchi <lucas.demarchi@intel.com>
- Patrick J.P <patrick.pereira@intel.com>
25c7e8b changed the logic of transfer(). Align
I2CDevice::read_registers_multiple() in the same way.
Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>
If I2CDevice::transfer() has to do nothing it returns false. This can be
misleading, as this might feel contradictory.
Let's spend a comment on that.
Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>
According to man 3 ioctl, ioctl returns other values than -1 on success.
So loop while ioctl returns -1.
Furthermore, there is no necessity to initialise r with -EINVAL,
Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>
We aren't going to use all the poller infra for now and we need it's
behavior a little bit different for what we are going to use:
- Do not use any "fair" time for each ready fd since we don't want
to set a timeout
- Allow to set the fd on Pollable after constructing it since we are
likely to embed Pollable inside other structs and just later be
able to open an fd.
- Let caller use the epoll flags directly - this is not in AP_HAL,
so there's no need to abstract them
Add system's polling infrastructure to be notified whenever a
file descriptor is ready to be read from or written to.
Adds a few classes:
* Poller, as an interface to epoll()
* Pollable, as an interface to a file descriptor
../../libraries/AP_HAL_Linux/SPIDevice.cpp: In member function ‘virtual AP_HAL::OwnPtr<AP_HAL::SPIDevice> Linux::SPIDeviceManager::get_device(const char*)’:
../../libraries/AP_HAL_Linux/SPIDevice.cpp:337:27: warning: comparison is always false due to limited range of data type [-Wtype-limits]
for (uint8_t i = 0; i < _n_device_desc; i++) {
~~^~~~~~~~~~~~~~~~
Define a dummy device to remove warning.
This centralized private header encourages centralizing things on
umbrella headers that are a pain to maintain. Force each part of
AP_HAL_Linux to include what is used.
Make some member variables protected to follow what we do in other
places (and there's no reason to be private).
Move defines to .cpp to reduce their visibility.
This centralized namespace header encourages centralizing things on
umbrella headers that are a pain to maintain. Force each part of
AP_HAL_Linux to include what is used.
While at it, do some whitespace cleanups and minor changes to adhere to
coding style.
This is selectable by a define and is never changed. Just remove
everything referencing it: we can come up with a better solution if it
is actually used later.
There's little point in having the Linux::AnalogIn just to implement and
empty interface. All implementations inside AP_HAL_Linux are already
inheriting directly from AP_HAL, so just remove it.
In a case ArduPilot is launched as a background process without
detaching with *nohup* like this ./arduplane -C /dev/ttyAMA0 ConsoleDevice
is created and an attempt to read from it is made. This yields in a stopped
process. This is an endeavour to overcome this problem.
Using factory method maked it easier to grasp the lifetime of all object
that get created and destroyed. Instead of spanning this thoughout whole
source file we have it nicely encapsulated in this a little horrendeous
_parseDevicePath that is of course to improve more.
Otherwise we're going to leak memory without any need.
Before this fix we've created ConsoleDevice 4 times in case -A switch hadn't been supplied,
but we hadn't ever deleted those. Now there's no memory leak here.
Minor changes to follow coding style and improve readability:
- sort headers
- move struct definition to compilation unit rather than header
- Add braces to if, for, etc