fixed a bunch of compiler warnings

mostly signed/unsigned warnings

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2884 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-07-17 10:30:21 +00:00
parent 8aad21fcc8
commit 855b88852e
6 changed files with 10 additions and 8 deletions

View File

@ -1041,7 +1041,7 @@ void
GCS_MAVLINK::_queued_send() GCS_MAVLINK::_queued_send()
{ {
// Check to see if we are sending parameters // Check to see if we are sending parameters
if (NULL != _queued_parameter && (requested_interface == chan) && mavdelay > 1) { if (NULL != _queued_parameter && (requested_interface == (unsigned)chan) && mavdelay > 1) {
AP_Var *vp; AP_Var *vp;
float value; float value;
@ -1074,8 +1074,8 @@ GCS_MAVLINK::_queued_send()
// request waypoints one by one // request waypoints one by one
// XXX note that this is pan-interface // XXX note that this is pan-interface
if (waypoint_receiving && if (waypoint_receiving &&
(requested_interface == chan) && (requested_interface == (unsigned)chan) &&
waypoint_request_i <= g.waypoint_total && waypoint_request_i <= (unsigned)g.waypoint_total &&
mavdelay > 15) { // limits to 3.33 hz mavdelay > 15) { // limits to 3.33 hz
mavlink_msg_waypoint_request_send( mavlink_msg_waypoint_request_send(

View File

@ -10,7 +10,7 @@
// These are function definitions so the Menu can be constructed before the functions // These are function definitions so the Menu can be constructed before the functions
// are defined below. Order matters to the compiler. // are defined below. Order matters to the compiler.
static int8_t print_log_menu(uint8_t argc, const Menu::arg *argv); static bool print_log_menu(void);
static int8_t dump_log(uint8_t argc, const Menu::arg *argv); static int8_t dump_log(uint8_t argc, const Menu::arg *argv);
static int8_t erase_logs(uint8_t argc, const Menu::arg *argv); static int8_t erase_logs(uint8_t argc, const Menu::arg *argv);
static int8_t select_logs(uint8_t argc, const Menu::arg *argv); static int8_t select_logs(uint8_t argc, const Menu::arg *argv);
@ -27,6 +27,7 @@ static int8_t help_log(uint8_t argc, const Menu::arg *argv)
" enable <name> | all\n" " enable <name> | all\n"
" disable <name> | all\n" " disable <name> | all\n"
"\n")); "\n"));
return 0;
} }
// Creates a constant array of structs representing menu options // Creates a constant array of structs representing menu options
@ -164,7 +165,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
// bits accordingly. // bits accordingly.
// //
if (!strcasecmp_P(argv[1].str, PSTR("all"))) { if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
bits = ~(bits = 0); bits = ~0;
bits = bits ^ MASK_LOG_SET_DEFAULTS; bits = bits ^ MASK_LOG_SET_DEFAULTS;
} else { } else {
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= MASK_LOG_ ## _s #define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= MASK_LOG_ ## _s
@ -753,7 +754,6 @@ void Log_Read(int start_page, int end_page)
{ {
byte data; byte data;
byte log_step = 0; byte log_step = 0;
int packet_count = 0;
int page = start_page; int page = start_page;
DataFlash.StartRead(start_page); DataFlash.StartRead(start_page);

View File

@ -546,7 +546,7 @@ void do_yaw()
bool verify_wait_delay() bool verify_wait_delay()
{ {
//Serial.print("vwd"); //Serial.print("vwd");
if ((millis() - condition_start) > condition_value){ if ((unsigned)(millis() - condition_start) > condition_value){
//Serial.println("y"); //Serial.println("y");
condition_value = 0; condition_value = 0;
return true; return true;

View File

@ -152,7 +152,7 @@ void throttle_failsafe(uint16_t pwm)
//check for failsafe and debounce funky reads //check for failsafe and debounce funky reads
// ------------------------------------------ // ------------------------------------------
if (pwm < g.throttle_fs_value){ if (pwm < (unsigned)g.throttle_fs_value){
// we detect a failsafe from radio // we detect a failsafe from radio
// throttle has dropped below the mark // throttle has dropped below the mark
failsafeCounter++; failsafeCounter++;

View File

@ -69,6 +69,7 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
// Run the setup menu. When the menu exits, we will return to the main menu. // Run the setup menu. When the menu exits, we will return to the main menu.
setup_menu.run(); setup_menu.run();
return 0;
} }
// Print the current configuration. // Print the current configuration.

View File

@ -85,6 +85,7 @@ test_mode(uint8_t argc, const Menu::arg *argv)
{ {
//Serial.printf_P(PSTR("Test Mode\n\n")); //Serial.printf_P(PSTR("Test Mode\n\n"));
test_menu.run(); test_menu.run();
return 0;
} }
static int8_t static int8_t