AP_Motors: get rid of _motor_to_channel_map

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 commit is contained in:
Lucas De Marchi 2015-09-29 11:58:52 +09:00 committed by Randy Mackay
parent 139b88f544
commit d97d97dc54
2 changed files with 9 additions and 17 deletions

View File

@ -24,9 +24,6 @@
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;
// initialise motor map
const uint8_t AP_Motors::_motor_to_channel_map[AP_MOTORS_MAX_NUM_MOTORS] PROGMEM = {MOTOR_TO_CHANNEL_MAP};
// Constructor
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
_roll_control_input(0.0f),

View File

@ -10,17 +10,15 @@
#include <RC_Channel/RC_Channel.h> // RC Channel Library
#include <Filter/Filter.h> // filter library
// offsets for motors in motor_out, _motor_filtered and _motor_to_channel_map arrays
#define AP_MOTORS_MOT_1 0
#define AP_MOTORS_MOT_2 1
#define AP_MOTORS_MOT_3 2
#define AP_MOTORS_MOT_4 3
#define AP_MOTORS_MOT_5 4
#define AP_MOTORS_MOT_6 5
#define AP_MOTORS_MOT_7 6
#define AP_MOTORS_MOT_8 7
#define MOTOR_TO_CHANNEL_MAP CH_1,CH_2,CH_3,CH_4,CH_5,CH_6,CH_7,CH_8
// offsets for motors in motor_out and _motor_filtered arrays
#define AP_MOTORS_MOT_1 0U
#define AP_MOTORS_MOT_2 1U
#define AP_MOTORS_MOT_3 2U
#define AP_MOTORS_MOT_4 3U
#define AP_MOTORS_MOT_5 4U
#define AP_MOTORS_MOT_6 5U
#define AP_MOTORS_MOT_7 6U
#define AP_MOTORS_MOT_8 7U
#define AP_MOTORS_MAX_NUM_MOTORS 8
@ -144,9 +142,6 @@ protected:
uint8_t interlock : 1; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)
} _flags;
// mapping of motor number (as received from upper APM code) to RC channel output - used to account for differences between APM1 and APM2
static const uint8_t _motor_to_channel_map[AP_MOTORS_MAX_NUM_MOTORS] PROGMEM;
// internal variables
float _roll_control_input; // desired roll control from attitude controllers, +/- 4500
float _pitch_control_input; // desired pitch control from attitude controller, +/- 4500