Browse Source

minor cleanup based on compiler warnings.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2122 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
jasonshort 14 years ago
parent
commit
6510b8df5a
  1. 16
      ArduCopterMega/ArduCopterMega.pde
  2. 2
      ArduCopterMega/Log.pde
  3. 5
      ArduCopterMega/Mavlink_Common.h
  4. 2
      ArduCopterMega/commands_logic.pde
  5. 35
      ArduCopterMega/read_commands.pde
  6. 16
      ArduCopterMega/setup.pde
  7. 3
      ArduCopterMega/system.pde
  8. 4
      ArduCopterMega/test.pde

16
ArduCopterMega/ArduCopterMega.pde

@ -391,7 +391,7 @@ struct Location prev_WP; // last waypoint
struct Location current_loc; // current location struct Location current_loc; // current location
struct Location next_WP; // next waypoint struct Location next_WP; // next waypoint
struct Location target_WP; // where do we want to you towards? struct Location target_WP; // where do we want to you towards?
struct Location tell_command; // command for telemetry struct Location simple_WP; // command for telemetry
struct Location next_command; // command preloaded struct Location next_command; // command preloaded
long target_altitude; // used for long target_altitude; // used for
boolean home_is_set; // Flag for if we have g_gps lock and have set the home location boolean home_is_set; // Flag for if we have g_gps lock and have set the home location
@ -965,16 +965,16 @@ void update_current_flight_mode(void)
if(flight_timer > 4){ if(flight_timer > 4){
flight_timer = 0; flight_timer = 0;
tell_command.lat = 0; simple_WP.lat = 0;
tell_command.lng = 0; simple_WP.lng = 0;
next_WP.lng = (float)g.rc_1.control_in *.4; // X: 4500 / 2 = 2250 = 25 meteres next_WP.lng = (float)g.rc_1.control_in *.4; // X: 4500 / 2 = 2250 = 25 meteres
next_WP.lat = -((float)g.rc_2.control_in *.4); // Y: 4500 / 2 = 2250 = 25 meteres next_WP.lat = -((float)g.rc_2.control_in *.4); // Y: 4500 / 2 = 2250 = 25 meteres
// calc a new bearing // calc a new bearing
nav_bearing = get_bearing(&tell_command, &next_WP) + initial_simple_bearing; nav_bearing = get_bearing(&simple_WP, &next_WP) + initial_simple_bearing;
nav_bearing = wrap_360(nav_bearing); nav_bearing = wrap_360(nav_bearing);
wp_distance = get_distance(&tell_command, &next_WP); wp_distance = get_distance(&simple_WP, &next_WP);
calc_bearing_error(); calc_bearing_error();
/* /*
Serial.printf("lat: %ld lon:%ld, bear:%ld, dist:%ld, init:%ld, err:%ld ", Serial.printf("lat: %ld lon:%ld, bear:%ld, dist:%ld, init:%ld, err:%ld ",
@ -1183,10 +1183,10 @@ void update_alt()
// XXX temp removed fr debugging // XXX temp removed fr debugging
//filter out bad sonar reads //filter out bad sonar reads
int temp = sonar.read(); int temp_sonar = sonar.read();
if(abs(temp - sonar_alt) < 300){ if(abs(temp_sonar - sonar_alt) < 300){
sonar_alt = temp; sonar_alt = temp_sonar;
} }
//sonar_alt = sonar.read(); //sonar_alt = sonar.read();

2
ArduCopterMega/Log.pde

@ -221,10 +221,8 @@ byte get_num_logs(void)
void start_new_log(byte num_existing_logs) void start_new_log(byte num_existing_logs)
{ {
int page;
int start_pages[50] = {0,0,0}; int start_pages[50] = {0,0,0};
int end_pages[50] = {0,0,0}; int end_pages[50] = {0,0,0};
byte data;
if (num_existing_logs > 0) { if (num_existing_logs > 0) {
for(int i=0;i<num_existing_logs;i++) { for(int i=0;i<num_existing_logs;i++) {

5
ArduCopterMega/Mavlink_Common.h

@ -83,7 +83,7 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
case MSG_ATTITUDE: case MSG_ATTITUDE:
{ {
Vector3f omega = dcm.get_gyro(); //Vector3f omega = dcm.get_gyro();
mavlink_msg_attitude_send( mavlink_msg_attitude_send(
chan, chan,
timeStamp, timeStamp,
@ -276,4 +276,5 @@ void mavlink_acknowledge(mavlink_channel_t chan, uint8_t id, uint8_t sum1, uint8
#endif // mavlink in use #endif // mavlink in use
#endif // inclusion guard #endif // inclusion guard

2
ArduCopterMega/commands_logic.pde

@ -370,7 +370,7 @@ bool verify_land()
//return true; //return true;
} }
//Serial.printf("N, %d\n", velocity_land); //Serial.printf("N, %d\n", velocity_land);
Serial.printf("N_alt, %d\n", next_WP.alt); Serial.printf("N_alt, %ld\n", next_WP.alt);
//update_crosstrack(); //update_crosstrack();
return false; return false;

35
ArduCopterMega/read_commands.pde

@ -5,32 +5,31 @@ char input_buffer[INPUT_BUF_LEN];
void readCommands(void) void readCommands(void)
{ {
static byte bufferPointer = 0;
static byte header[2]; static byte header[2];
const byte read_GS_header[] = {0x21, 0x21}; //!! Used to verify the payload msg header const byte read_GS_header[] = {0x21, 0x21}; //!! Used to verify the payload msg header
if(Serial.available()){ if(Serial.available()){
//Serial.println("Serial.available"); //Serial.println("Serial.available");
byte bufferPointer; byte bufferPointer;
header[0] = Serial.read(); header[0] = Serial.read();
header[1] = Serial.read(); header[1] = Serial.read();
if((header[0] == read_GS_header[0]) && (header[1] == read_GS_header[1])){ if((header[0] == read_GS_header[0]) && (header[1] == read_GS_header[1])){
// Block until we read full command // Block until we read full command
// -------------------------------- // --------------------------------
delay(20); delay(20);
byte incoming_val = 0; byte incoming_val = 0;
// Ground Station communication // Ground Station communication
// ---------------------------- // ----------------------------
while(Serial.available() > 0) while(Serial.available() > 0)
{ {
incoming_val = Serial.read(); incoming_val = Serial.read();
if (incoming_val != 13 && incoming_val != 10 ) { if (incoming_val != 13 && incoming_val != 10 ) {
input_buffer[bufferPointer++] = incoming_val; input_buffer[bufferPointer++] = incoming_val;
} }
if(bufferPointer >= INPUT_BUF_LEN){ if(bufferPointer >= INPUT_BUF_LEN){
@ -43,7 +42,7 @@ void readCommands(void)
} }
} }
parseCommand(input_buffer); parseCommand(input_buffer);
// clear buffer of old data // clear buffer of old data
// ------------------------ // ------------------------
memset(input_buffer,0,sizeof(input_buffer)); memset(input_buffer,0,sizeof(input_buffer));
@ -61,14 +60,14 @@ void parseCommand(char *buffer)
Serial.println("got cmd "); Serial.println("got cmd ");
Serial.println(buffer); Serial.println(buffer);
char *token, *saveptr1, *saveptr2; char *token, *saveptr1, *saveptr2;
for (int j = 1;; j++, buffer = NULL) { for (int j = 1;; j++, buffer = NULL) {
token = strtok_r(buffer, "|", &saveptr1); token = strtok_r(buffer, "|", &saveptr1);
if (token == NULL) break; if (token == NULL) break;
char * cmd = strtok_r(token, ":", &saveptr2); char * cmd = strtok_r(token, ":", &saveptr2);
long value = strtol(strtok_r (NULL,":", &saveptr2), NULL,0); long value = strtol(strtok_r (NULL,":", &saveptr2), NULL,0);
///* ///*
Serial.print("cmd "); Serial.print("cmd ");
Serial.print(cmd[0]); Serial.print(cmd[0]);
@ -94,7 +93,7 @@ void parseCommand(char *buffer)
//g.pid_stabilize_roll.kD((float)value / 1000); //g.pid_stabilize_roll.kD((float)value / 1000);
//g.pid_stabilize_pitch.kD((float)value / 1000); //g.pid_stabilize_pitch.kD((float)value / 1000);
break; break;
case 'X': case 'X':
g.pid_stabilize_roll.imax(value * 100); g.pid_stabilize_roll.imax(value * 100);
g.pid_stabilize_pitch.imax(value * 100); g.pid_stabilize_pitch.imax(value * 100);
@ -106,7 +105,7 @@ void parseCommand(char *buffer)
break; break;
} }
init_pids(); init_pids();
//*/ //*/
} }
} }

16
ArduCopterMega/setup.pde

@ -67,7 +67,6 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
static int8_t static int8_t
setup_show(uint8_t argc, const Menu::arg *argv) setup_show(uint8_t argc, const Menu::arg *argv)
{ {
uint8_t i;
// clear the area // clear the area
print_blanks(8); print_blanks(8);
@ -92,9 +91,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
static int8_t static int8_t
setup_factory(uint8_t argc, const Menu::arg *argv) setup_factory(uint8_t argc, const Menu::arg *argv)
{ {
int c;
uint8_t i;
int c;
Serial.printf_P(PSTR("\n'Y' + Enter to factory reset, any other key to abort:\n")); Serial.printf_P(PSTR("\n'Y' + Enter to factory reset, any other key to abort:\n"));
@ -200,7 +197,8 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
static int8_t static int8_t
setup_esc(uint8_t argc, const Menu::arg *argv) setup_esc(uint8_t argc, const Menu::arg *argv)
{ {
Serial.printf_P(PSTR("\nUnplug battery, calibrate as usual.\n Press Enter to cancel.\n")); Serial.printf_P(PSTR("\nUnplug, then plug-in battery; Calibrate ESCs.\n Press Enter to cancel.\n"));
g.esc_calibrate.set_and_save(1); g.esc_calibrate.set_and_save(1);
@ -209,7 +207,7 @@ setup_esc(uint8_t argc, const Menu::arg *argv)
if(Serial.available() > 0){ if(Serial.available() > 0){
g.esc_calibrate.set_and_save(0); g.esc_calibrate.set_and_save(0);
break; return(0);
} }
} }
} }
@ -409,7 +407,7 @@ setup_pid(uint8_t argc, const Menu::arg *argv)
static int8_t static int8_t
setup_flightmodes(uint8_t argc, const Menu::arg *argv) setup_flightmodes(uint8_t argc, const Menu::arg *argv)
{ {
byte switchPosition, oldSwitchPosition, mode; byte switchPosition, _oldSwitchPosition, mode;
Serial.printf_P(PSTR("\nMove RC toggle switch to each position to edit, move aileron stick to select modes.")); Serial.printf_P(PSTR("\nMove RC toggle switch to each position to edit, move aileron stick to select modes."));
print_hit_enter(); print_hit_enter();
@ -421,7 +419,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
// look for control switch change // look for control switch change
if (oldSwitchPosition != switchPosition){ if (_oldSwitchPosition != switchPosition){
mode = g.flight_modes[switchPosition]; mode = g.flight_modes[switchPosition];
mode = constrain(mode, 0, NUM_MODES-1); mode = constrain(mode, 0, NUM_MODES-1);
@ -430,7 +428,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
print_switch(switchPosition, mode); print_switch(switchPosition, mode);
// Remember switch position // Remember switch position
oldSwitchPosition = switchPosition; _oldSwitchPosition = switchPosition;
} }
// look for stick input // look for stick input

3
ArduCopterMega/system.pde

@ -119,7 +119,7 @@ void init_ardupilot()
} }
}else{ }else{
unsigned long before = micros(); // unsigned long before = micros();
// Load all auto-loaded EEPROM variables // Load all auto-loaded EEPROM variables
AP_Var::load_all(); AP_Var::load_all();
@ -263,7 +263,6 @@ void startup_ground(void)
// ------------------- // -------------------
init_commands(); init_commands();
byte counter = 4;
GPS_enabled = false; GPS_enabled = false;
// Read in the GPS // Read in the GPS

4
ArduCopterMega/test.pde

@ -842,8 +842,6 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
static int8_t static int8_t
test_mission(uint8_t argc, const Menu::arg *argv) test_mission(uint8_t argc, const Menu::arg *argv)
{ {
//print_hit_enter();
//delay(1000);
//write out a basic mission to the EEPROM //write out a basic mission to the EEPROM
Location t; Location t;
/*{ /*{
@ -911,7 +909,7 @@ void fake_out_gps()
g_gps->new_data = true; g_gps->new_data = true;
g_gps->fix = true; g_gps->fix = true;
int length = g.rc_6.control_in; //int length = g.rc_6.control_in;
rads += .05; rads += .05;
if (rads > 6.28){ if (rads > 6.28){

Loading…
Cancel
Save