Browse Source

ArduPlane: replaced many "int" with "int16_t", "long" with "int32_t"

master
rmackay9 13 years ago
parent
commit
6d489947cf
  1. 2
      ArduPlane/ArduPlane.pde
  2. 6
      ArduPlane/Attitude.pde
  3. 12
      ArduPlane/GCS_Mavlink.pde
  4. 2
      ArduPlane/Parameters.pde
  5. 8
      ArduPlane/commands.pde
  6. 4
      ArduPlane/events.pde
  7. 2
      ArduPlane/planner.pde
  8. 8
      ArduPlane/setup.pde
  9. 8
      ArduPlane/test.pde

2
ArduPlane/ArduPlane.pde

@ -631,7 +631,7 @@ static float G_Dt = 0.02;
// Timer used to accrue data and trigger recording of the performanc monitoring log message // Timer used to accrue data and trigger recording of the performanc monitoring log message
static int32_t perf_mon_timer; static int32_t perf_mon_timer;
// The maximum main loop execution time recorded in the current performance monitoring interval // The maximum main loop execution time recorded in the current performance monitoring interval
static int G_Dt_max = 0; static int16_t G_Dt_max = 0;
// The number of gps fixes recorded in the current performance monitoring interval // The number of gps fixes recorded in the current performance monitoring interval
static int16_t gps_fix_count = 0; static int16_t gps_fix_count = 0;
// A variable used by developers to track performanc metrics. // A variable used by developers to track performanc metrics.

6
ArduPlane/Attitude.pde

@ -133,7 +133,7 @@ static void crash_checker()
static void calc_throttle() static void calc_throttle()
{ {
if (!airspeed.use()) { if (!airspeed.use()) {
int throttle_target = g.throttle_cruise + throttle_nudge; int16_t throttle_target = g.throttle_cruise + throttle_nudge;
// TODO: think up an elegant way to bump throttle when // TODO: think up an elegant way to bump throttle when
// groundspeed_undershoot > 0 in the no airspeed sensor case; PID // groundspeed_undershoot > 0 in the no airspeed sensor case; PID
@ -255,7 +255,7 @@ float roll_slew_limit(float servo)
*****************************************/ *****************************************/
static void throttle_slew_limit() static void throttle_slew_limit()
{ {
static int last = 1000; static int16_t last = 1000;
if(g.throttle_slewrate) { // if slew limit rate is set to zero then do not slew limit if(g.throttle_slewrate) { // if slew limit rate is set to zero then do not slew limit
float temp = g.throttle_slewrate * G_Dt * 10.f; // * 10 to scale % to pwm range of 1000 to 2000 float temp = g.throttle_slewrate * G_Dt * 10.f; // * 10 to scale % to pwm range of 1000 to 2000
@ -281,7 +281,7 @@ static void reset_I(void)
*****************************************/ *****************************************/
static void set_servos(void) static void set_servos(void)
{ {
int flapSpeedSource = 0; int16_t flapSpeedSource = 0;
// vectorize the rc channels // vectorize the rc channels
RC_Channel_aux* rc_array[NUM_CHANNELS]; RC_Channel_aux* rc_array[NUM_CHANNELS];

12
ArduPlane/GCS_Mavlink.pde

@ -474,7 +474,7 @@ static void NOINLINE send_statustext(mavlink_channel_t chan)
// try to send a message, return false if it won't fit in the serial tx buffer // try to send a message, return false if it won't fit in the serial tx buffer
static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops) static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops)
{ {
int payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES; int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) { if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) {
// defer any messages on the telemetry port for 1 second after // defer any messages on the telemetry port for 1 second after
@ -946,7 +946,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (mavlink_check_target(packet.target_system, packet.target_component)) if (mavlink_check_target(packet.target_system, packet.target_component))
break; break;
int freq = 0; // packet frequency int16_t freq = 0; // packet frequency
if (packet.start_stop == 0) if (packet.start_stop == 0)
freq = 0; // stop sending freq = 0; // stop sending
@ -1963,10 +1963,10 @@ GCS_MAVLINK::queued_waypoint_send()
MAVLink to process packets while waiting for the initialisation to MAVLink to process packets while waiting for the initialisation to
complete complete
*/ */
static void mavlink_delay(unsigned long t) static void mavlink_delay(uint32_t t)
{ {
unsigned long tstart; uint32_t tstart;
static unsigned long last_1hz, last_50hz, last_5s; static uint32_t last_1hz, last_50hz, last_5s;
if (in_mavlink_delay) { if (in_mavlink_delay) {
// this should never happen, but let's not tempt fate by // this should never happen, but let's not tempt fate by
@ -1979,7 +1979,7 @@ static void mavlink_delay(unsigned long t)
tstart = millis(); tstart = millis();
do { do {
unsigned long tnow = millis(); uint32_t tnow = millis();
if (tnow - last_1hz > 1000) { if (tnow - last_1hz > 1000) {
last_1hz = tnow; last_1hz = tnow;
gcs_send_message(MSG_HEARTBEAT); gcs_send_message(MSG_HEARTBEAT);

2
ArduPlane/Parameters.pde

@ -609,7 +609,7 @@ static void load_parameters(void)
g.format_version.set_and_save(Parameters::k_format_version); g.format_version.set_and_save(Parameters::k_format_version);
Serial.println_P(PSTR("done.")); Serial.println_P(PSTR("done."));
} else { } else {
unsigned long before = micros(); uint32_t before = micros();
// Load all auto-loaded EEPROM variables // Load all auto-loaded EEPROM variables
AP_Param::load_all(); AP_Param::load_all();

8
ArduPlane/commands.pde

@ -40,10 +40,10 @@ static void reload_commands_airstart()
// Getters // Getters
// ------- // -------
static struct Location get_cmd_with_index(int i) static struct Location get_cmd_with_index(int16_t i)
{ {
struct Location temp; struct Location temp;
long mem; int32_t mem;
// Find out proper location in memory by using the start_byte position + the index // Find out proper location in memory by using the start_byte position + the index
// -------------------------------------------------------------------------------- // --------------------------------------------------------------------------------
@ -83,7 +83,7 @@ static struct Location get_cmd_with_index(int i)
// Setters // Setters
// ------- // -------
static void set_cmd_with_index(struct Location temp, int i) static void set_cmd_with_index(struct Location temp, int16_t i)
{ {
i = constrain(i, 0, g.command_total.get()); i = constrain(i, 0, g.command_total.get());
intptr_t mem = WP_START_BYTE + (i * WP_SIZE); intptr_t mem = WP_START_BYTE + (i * WP_SIZE);
@ -121,7 +121,7 @@ static void decrement_cmd_index()
} }
} }
static long read_alt_to_hold() static int32_t read_alt_to_hold()
{ {
if (g.RTL_altitude_cm < 0) { if (g.RTL_altitude_cm < 0) {
return current_loc.alt; return current_loc.alt;

4
ArduPlane/events.pde

@ -1,7 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void failsafe_short_on_event(int fstype) static void failsafe_short_on_event(int16_t fstype)
{ {
// This is how to handle a short loss of control signal failsafe. // This is how to handle a short loss of control signal failsafe.
failsafe = fstype; failsafe = fstype;
@ -32,7 +32,7 @@ static void failsafe_short_on_event(int fstype)
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode); gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
} }
static void failsafe_long_on_event(int fstype) static void failsafe_long_on_event(int16_t fstype)
{ {
// This is how to handle a long loss of control signal failsafe. // This is how to handle a long loss of control signal failsafe.
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on, ")); gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on, "));

2
ArduPlane/planner.pde

@ -32,7 +32,7 @@ planner_gcs(uint8_t argc, const Menu::arg *argv)
gcs3.init(&Serial3); gcs3.init(&Serial3);
#endif #endif
int loopcount = 0; int16_t loopcount = 0;
while (1) { while (1) {
if (millis()-fast_loopTimer_ms > 19) { if (millis()-fast_loopTimer_ms > 19) {
fast_loopTimer_ms = millis(); fast_loopTimer_ms = millis();

8
ArduPlane/setup.pde

@ -217,7 +217,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
} }
// look for stick input // look for stick input
int radioInputSwitch = radio_input_switch(); int16_t radioInputSwitch = radio_input_switch();
if (radioInputSwitch != 0){ if (radioInputSwitch != 0){
@ -480,7 +480,7 @@ static void report_flight_modes()
Serial.printf_P(PSTR("Flight modes\n")); Serial.printf_P(PSTR("Flight modes\n"));
print_divider(); print_divider();
for(int i = 0; i < 6; i++ ){ for(int16_t i = 0; i < 6; i++ ){
print_switch(i, flight_modes[i]); print_switch(i, flight_modes[i]);
} }
print_blanks(2); print_blanks(2);
@ -528,7 +528,7 @@ print_done()
} }
static void static void
print_blanks(int num) print_blanks(int16_t num)
{ {
while(num > 0){ while(num > 0){
num--; num--;
@ -539,7 +539,7 @@ print_blanks(int num)
static void static void
print_divider(void) print_divider(void)
{ {
for (int i = 0; i < 40; i++) { for (int16_t i = 0; i < 40; i++) {
Serial.printf_P(PSTR("-")); Serial.printf_P(PSTR("-"));
} }
Serial.println(""); Serial.println("");

8
ArduPlane/test.pde

@ -137,7 +137,7 @@ test_passthru(uint8_t argc, const Menu::arg *argv)
// New radio frame? (we could use also if((millis()- timer) > 20) // New radio frame? (we could use also if((millis()- timer) > 20)
if (APM_RC.GetState() == 1){ if (APM_RC.GetState() == 1){
Serial.print("CH:"); Serial.print("CH:");
for(int i = 0; i < 8; i++){ for(int16_t i = 0; i < 8; i++){
Serial.print(APM_RC.InputCh(i)); // Print channel values Serial.print(APM_RC.InputCh(i)); // Print channel values
Serial.print(","); Serial.print(",");
APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos
@ -195,7 +195,7 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
{ {
byte fail_test; byte fail_test;
print_hit_enter(); print_hit_enter();
for(int i = 0; i < 50; i++){ for(int16_t i = 0; i < 50; i++){
delay(20); delay(20);
read_radio(); read_radio();
} }
@ -423,7 +423,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
delay(1000); delay(1000);
while(1){ while(1){
for (int i=0;i<9;i++) Serial.printf_P(PSTR("%.1f\t"),adc.Ch(i)); for (int16_t i=0;i<9;i++) Serial.printf_P(PSTR("%.1f\t"),adc.Ch(i));
Serial.println(); Serial.println();
delay(100); delay(100);
if(Serial.available() > 0){ if(Serial.available() > 0){
@ -531,7 +531,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
imu.init(IMU::COLD_START, delay, flash_leds, &timer_scheduler); imu.init(IMU::COLD_START, delay, flash_leds, &timer_scheduler);
ahrs.reset(); ahrs.reset();
int counter = 0; int16_t counter = 0;
float heading = 0; float heading = 0;
//Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION); //Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION);

Loading…
Cancel
Save