In 294298e ("AP_InertialSensor: use method for downcast") I was too eager
to use "auto" and ended up using the implicit copy constructor instead
of actually getting a reference to the object.
This was only used for supporting APM1. The removal was mostly automatic
with:
sed -i 's/pgm_read_byte(&_motor_to_channel_map\[\([^]]*\)\])/\1/g' libraries/AP_Motors/*.cpp
sed -i 's/_motor_to_channel_map\[\([^]]*\)\]/\1/g' libraries/AP_Motors/*.cpp
And then remove references to MOTOR_TO_CHANNEL_MAP and
_motor_to_channel_map and make sure the variable used in shifts is
unsigned
This method is not used anymore since the introduction of channel map and
allowing motors to be enabled/disabled in AP_Motors.
Later we may introduce a method to write multiple values with a default
implementation that supports the channel and enable maps rather than
requiring all subclasses to implement this method.
This is the only place where this variant of RCOutput::write() is
called. Remove it so to use the common interface. It can be added back
later when there's support for asynchronous write.
Now that most places in the code use the ARRAY_SIZE macro instead of
coding it by hand, let's use some type safety in its definition. This is
a C++ version of similar macros used in kmod, Linux kernel and the
source of them, ccan.
A C++ version like this is used in V8 (the JS engine) and other open
source projects.
The main benefit of this version is that you get a compile error if you
pass in a variable that's not an array. For example,
Bla y[10];
Bla *y_ptr = y;
void foo(Bla x[])
{
// build error since x[] decay to a pointer in function
// parameter
for (int i = 0; i < ARRAY_SIZE(x); i++) {
...
}
// build error since y_ptr is not an array
for (int i = 0; i < ARRAY_SIZE(y_ptr); i++) {
...
}
}
I added the additional specialization to allow arrays of size 0.