From 7809b0ca2a745f5e224103358abecd95f47ba419 Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Wed, 4 May 2011 19:12:27 +0000 Subject: [PATCH] Massive warning fixes. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2089 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/APM_BMP085/APM_BMP085.cpp | 7 +++---- libraries/AP_ADC/AP_ADC.cpp | 12 ------------ libraries/AP_ADC/AP_ADC.h | 6 +++--- libraries/AP_ADC/AP_ADC_ADS7844.cpp | 4 +--- libraries/AP_ADC/AP_ADC_HIL.cpp | 2 +- libraries/AP_ADC/AP_ADC_HIL.h | 2 +- libraries/AP_Common/AP_Loop.cpp | 8 ++++---- libraries/AP_Common/AP_Loop.h | 4 ++-- libraries/AP_Common/AP_Var.cpp | 8 ++++---- libraries/AP_Common/AP_Vector.h | 14 +++++++------- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 1 - libraries/AP_GPS/AP_GPS_Auto.cpp | 3 ++- libraries/AP_GPS/AP_GPS_IMU.cpp | 8 ++++---- libraries/AP_GPS/AP_GPS_MTK.h | 4 ++-- libraries/AP_GPS/AP_GPS_MTK16.h | 4 ++-- libraries/AP_GPS/AP_GPS_NMEA.cpp | 2 -- libraries/AP_GPS/AP_GPS_SIRF.h | 4 ++-- libraries/AP_GPS/AP_GPS_Shim.h | 2 +- libraries/AP_GPS/AP_GPS_UBLOX.h | 4 ++-- libraries/AP_GPS/GPS.cpp | 4 ++-- .../AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h | 2 +- libraries/AP_RangeFinder/RangeFinder.cpp | 7 +++++-- libraries/AP_RangeFinder/RangeFinder.h | 4 ++-- .../AP_RangeFinder_test/AP_RangeFinder_test.pde | 1 - libraries/FastSerial/FastSerial.cpp | 2 +- libraries/FastSerial/FastSerial.h | 5 +++-- libraries/FastSerial/vprintf.cpp | 2 +- libraries/GCS_MAVLink/GCS_MAVLink.h | 6 ++++++ libraries/GCS_MAVLink/include/protocol.h | 2 +- 31 files changed, 65 insertions(+), 73 deletions(-) diff --git a/libraries/APM_BMP085/APM_BMP085.cpp b/libraries/APM_BMP085/APM_BMP085.cpp index d3c1872fec..c66506dffc 100644 --- a/libraries/APM_BMP085/APM_BMP085.cpp +++ b/libraries/APM_BMP085/APM_BMP085.cpp @@ -1,6 +1,6 @@ /* APM_BMP085.cpp - Arduino Library for BMP085 absolute pressure sensor - Code by Jordi Muñoz and Jose Julio. DIYDrones.com + Code by Jordi Mu�oz and Jose Julio. DIYDrones.com This library is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public @@ -14,13 +14,13 @@ RawTemp : Raw temperature data RawPress : Raw pressure data - Temp : Calculated temperature (in 0.1ºC units) + Temp : Calculated temperature (in 0.1�C units) Press : Calculated pressure (in Pa units) Methods: Init() : Initialization of I2C and read sensor calibration data Read() : Read sensor data and calculate Temperature and Pressure - This function is optimized so the main host don´t need to wait + This function is optimized so the main host don�t need to wait You can call this function in your main loop It returns a 1 if there are new data. @@ -54,7 +54,6 @@ APM_BMP085_Class::APM_BMP085_Class() // Public Methods ////////////////////////////////////////////////////////////// void APM_BMP085_Class::Init(int initialiseWireLib) { - unsigned char tmp; byte buff[22]; int i=0; diff --git a/libraries/AP_ADC/AP_ADC.cpp b/libraries/AP_ADC/AP_ADC.cpp index fa784ebb30..d673d4504a 100644 --- a/libraries/AP_ADC/AP_ADC.cpp +++ b/libraries/AP_ADC/AP_ADC.cpp @@ -9,15 +9,3 @@ */ #include "AP_ADC.h" - -AP_ADC::AP_ADC() -{ -} - -void AP_ADC::Init() -{ -} - -int AP_ADC::Ch(unsigned char ch_num) -{ -} diff --git a/libraries/AP_ADC/AP_ADC.h b/libraries/AP_ADC/AP_ADC.h index 3957705658..f99971c54a 100644 --- a/libraries/AP_ADC/AP_ADC.h +++ b/libraries/AP_ADC/AP_ADC.h @@ -19,9 +19,9 @@ class AP_ADC { public: - AP_ADC(); // Constructor - virtual void Init(); - virtual int Ch(unsigned char ch_num); + AP_ADC() {}; // Constructor + virtual void Init() {}; + virtual int Ch(unsigned char ch_num) = 0; private: }; diff --git a/libraries/AP_ADC/AP_ADC_ADS7844.cpp b/libraries/AP_ADC/AP_ADC_ADS7844.cpp index 6936a7bbaa..723181dfc8 100644 --- a/libraries/AP_ADC/AP_ADC_ADS7844.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS7844.cpp @@ -1,6 +1,6 @@ /* AP_ADC_ADS7844.cpp - ADC ADS7844 Library for Ardupilot Mega - Code by Jordi Muñoz and Jose Julio. DIYDrones.com + Code by Jordi Mu�oz and Jose Julio. DIYDrones.com Modified by John Ihlein 6/19/2010 to: 1)Prevent overflow of adc_counter when more than 8 samples collected between reads. Probably @@ -103,8 +103,6 @@ AP_ADC_ADS7844::AP_ADC_ADS7844() // Public Methods ////////////////////////////////////////////////////////////// void AP_ADC_ADS7844::Init(void) { - unsigned char tmp; - pinMode(ADC_CHIP_SELECT,OUTPUT); digitalWrite(ADC_CHIP_SELECT,HIGH); // Disable device (Chip select is active low) diff --git a/libraries/AP_ADC/AP_ADC_HIL.cpp b/libraries/AP_ADC/AP_ADC_HIL.cpp index da15c885f4..70465eaf17 100644 --- a/libraries/AP_ADC/AP_ADC_HIL.cpp +++ b/libraries/AP_ADC/AP_ADC_HIL.cpp @@ -48,7 +48,7 @@ int AP_ADC_HIL::Ch(unsigned char ch_num) } // Set one channel value -int AP_ADC_HIL::setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp, +void AP_ADC_HIL::setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp, int16_t aX, int16_t aY, int16_t aZ, int16_t diffPress) { // gyros diff --git a/libraries/AP_ADC/AP_ADC_HIL.h b/libraries/AP_ADC/AP_ADC_HIL.h index c4531ab61d..4a9ddacf3a 100644 --- a/libraries/AP_ADC/AP_ADC_HIL.h +++ b/libraries/AP_ADC/AP_ADC_HIL.h @@ -37,7 +37,7 @@ class AP_ADC_HIL : public AP_ADC /// // Set the adc raw values given the current rotations rates, // temps, accels, and pressures - int setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp, + void setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp, int16_t aX, int16_t aY, int16_t aZ, int16_t diffPress); private: diff --git a/libraries/AP_Common/AP_Loop.cpp b/libraries/AP_Common/AP_Loop.cpp index 82040d72ee..031c59c982 100644 --- a/libraries/AP_Common/AP_Loop.cpp +++ b/libraries/AP_Common/AP_Loop.cpp @@ -18,12 +18,12 @@ #include "AP_Loop.h" -Loop::Loop(float frequency, void (*fptr)(void *), void * data) : +Loop::Loop(float _frequency, void (*fptr)(void *), void * data) : _fptr(fptr), _data(data), - _period(1.0e6/frequency), - _timeStamp(micros()), + _period(1.0e6/_frequency), _subLoops(), + _timeStamp(micros()), _load(0), _dt(0) { @@ -40,7 +40,7 @@ void Loop::update() _dt = (_timeStamp - timeStamp0)/1.0e6; // update sub loops - for (int i=0; i<_subLoops.getSize(); i++) _subLoops[i]->update(); + for (uint8_t i=0; i<_subLoops.getSize(); i++) _subLoops[i]->update(); // callback function if (_fptr) _fptr(_data); diff --git a/libraries/AP_Common/AP_Loop.h b/libraries/AP_Common/AP_Loop.h index c41935c8aa..ef2ebe25c6 100644 --- a/libraries/AP_Common/AP_Loop.h +++ b/libraries/AP_Common/AP_Loop.h @@ -33,8 +33,8 @@ public: uint32_t frequency() { return 1.0e6/_period; } - void frequency(float frequency) { - _period = 1e6/frequency; + void frequency(float _frequency) { + _period = 1e6/_frequency; } uint32_t timeStamp() { return _timeStamp; diff --git a/libraries/AP_Common/AP_Var.cpp b/libraries/AP_Common/AP_Var.cpp index c45155998e..974a74ca11 100644 --- a/libraries/AP_Common/AP_Var.cpp +++ b/libraries/AP_Common/AP_Var.cpp @@ -37,9 +37,9 @@ uint16_t AP_Var::_bytes_in_use; // Constructor for standalone variables // -AP_Var::AP_Var(Key key, const prog_char_t *name, Flags flags) : +AP_Var::AP_Var(Key p_key, const prog_char_t *name, Flags flags) : _group(NULL), - _key(key | k_key_not_located), + _key(p_key | k_key_not_located), _name(name), _flags(flags) { @@ -54,8 +54,8 @@ AP_Var::AP_Var(Key key, const prog_char_t *name, Flags flags) : // Constructor for variables in a group // -AP_Var::AP_Var(AP_Var_group *group, Key index, const prog_char_t *name, Flags flags) : - _group(group), +AP_Var::AP_Var(AP_Var_group *pGroup, Key index, const prog_char_t *name, Flags flags) : + _group(pGroup), _key(index), _name(name), _flags(flags) diff --git a/libraries/AP_Common/AP_Vector.h b/libraries/AP_Common/AP_Vector.h index 1d25721273..287056b2a1 100644 --- a/libraries/AP_Common/AP_Vector.h +++ b/libraries/AP_Common/AP_Vector.h @@ -38,8 +38,8 @@ private: dataType* data; public: // default constructor - Vector(const size_t & size=0, const size_t & extraAllocationSize=0) : size(0), extraAllocationSize(extraAllocationSize), sizeAllocated(0), data(NULL) { - setSize(size); + Vector(const size_t & _size=0, const size_t & _extraAllocationSize=0) : size(0), extraAllocationSize(_extraAllocationSize), sizeAllocated(0), data(NULL) { + setSize(_size); } // 3 vector constructor Vector(const dataType & a, const dataType & b, const dataType & c) : size(3), extraAllocationSize(extraAllocationSize), sizeAllocated(0), data(NULL) { @@ -50,8 +50,8 @@ public: } // construct from array - Vector(const dataType* array, const size_t & size, const size_t & extraAllocationSize=0) : size(0), extraAllocationSize(extraAllocationSize), sizeAllocated(0), data(NULL) { - setSize(size); + Vector(const dataType* array, const size_t & _size, const size_t & _extraAllocationSize=0) : size(0), extraAllocationSize(_extraAllocationSize), sizeAllocated(0), data(NULL) { + setSize(_size); for (size_t i=0; iavailable(); @@ -152,6 +151,7 @@ AP_GPS_IMU::read(void) } }// End for... } + return true; } /**************************************************************** @@ -229,5 +229,5 @@ void AP_GPS_IMU::checksum(byte data) /**************************************************************** * Unused ****************************************************************/ -void AP_GPS_IMU::setHIL(long time, float latitude, float longitude, float altitude, - float ground_speed, float ground_course, float speed_3d, uint8_t num_sats) {}; \ No newline at end of file +void AP_GPS_IMU::setHIL(long _time, float _latitude, float _longitude, float _altitude, + float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats) {}; diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index bae99f1c41..8f37a635d3 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -25,7 +25,7 @@ public: virtual bool read(void); private: -#pragma pack(1) +// XXX this is being ignored by the compiler #pragma pack(1) struct diyd_mtk_msg { int32_t latitude; int32_t longitude; @@ -36,7 +36,7 @@ private: uint8_t fix_type; uint32_t utc_time; }; -#pragma pack(pop) +// #pragma pack(pop) enum diyd_mtk_fix_type { FIX_NONE = 1, FIX_2D = 2, diff --git a/libraries/AP_GPS/AP_GPS_MTK16.h b/libraries/AP_GPS/AP_GPS_MTK16.h index 78c29ebb21..46a7bceb23 100644 --- a/libraries/AP_GPS/AP_GPS_MTK16.h +++ b/libraries/AP_GPS/AP_GPS_MTK16.h @@ -23,7 +23,7 @@ public: virtual bool read(void); private: -#pragma pack(1) +// XXX this is being ignored by the compiler #pragma pack(1) struct diyd_mtk_msg { int32_t latitude; int32_t longitude; @@ -36,7 +36,7 @@ private: uint32_t utc_time; uint16_t hdop; }; -#pragma pack(pop) +// #pragma pack(pop) enum diyd_mtk_fix_type { FIX_NONE = 1, FIX_2D = 2, diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index e16601c513..e60b18fd51 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -120,7 +120,6 @@ void AP_GPS_NMEA::init(void) bool AP_GPS_NMEA::read(void) { - char data; int numc; bool parsed = false; @@ -204,7 +203,6 @@ unsigned long AP_GPS_NMEA::_parse_degrees() char *p, *q; uint8_t deg = 0, min = 0; unsigned int frac_min = 0; - unsigned long result; // scan for decimal point or end of field for (p = _term; isdigit(*p); p++) diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h index dd20ea726d..483d7cefca 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.h +++ b/libraries/AP_GPS/AP_GPS_SIRF.h @@ -23,7 +23,7 @@ public: virtual bool read(); private: -#pragma pack(1) +// XXX this is being ignored by the compiler #pragma pack(1) struct sirf_geonav { uint16_t fix_invalid; uint16_t fix_type; @@ -61,7 +61,7 @@ private: uint8_t hdop; uint8_t mode_info; }; -#pragma pack(pop) +// #pragma pack(pop) enum sirf_protocol_bytes { PREAMBLE1 = 0xa0, PREAMBLE2 = 0xa2, diff --git a/libraries/AP_GPS/AP_GPS_Shim.h b/libraries/AP_GPS/AP_GPS_Shim.h index ce7828d588..c96ceb927e 100644 --- a/libraries/AP_GPS/AP_GPS_Shim.h +++ b/libraries/AP_GPS/AP_GPS_Shim.h @@ -23,7 +23,7 @@ public: virtual bool read(void) { bool updated = _updated; _updated = false; - return _updated; + return updated; } /// Set-and-mark-updated macro for the public member variables; each instance diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index cbb7b29df8..02fc0f7be4 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -25,7 +25,7 @@ public: private: // u-blox UBX protocol essentials -#pragma pack(1) +// XXX this is being ignored by the compiler #pragma pack(1) struct ubx_nav_posllh { uint32_t time; // GPS msToW int32_t longitude; @@ -74,7 +74,7 @@ private: uint32_t speed_accuracy; uint32_t heading_accuracy; }; -#pragma pack(pop) +// // #pragma pack(pop) enum ubs_protocol_bytes { PREAMBLE1 = 0xb5, PREAMBLE2 = 0x62, diff --git a/libraries/AP_GPS/GPS.cpp b/libraries/AP_GPS/GPS.cpp index a85e936130..ad0a4d5ce4 100644 --- a/libraries/AP_GPS/GPS.cpp +++ b/libraries/AP_GPS/GPS.cpp @@ -33,8 +33,8 @@ GPS::update(void) } void -GPS::setHIL(long time, float latitude, float longitude, float altitude, - float ground_speed, float ground_course, float speed_3d, uint8_t num_sats) +GPS::setHIL(long _time, float _latitude, float _longitude, float _altitude, + float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats) { } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h index c710b13828..580091a101 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarLV.h @@ -10,6 +10,6 @@ class AP_RangeFinder_MaxsonarLV : public RangeFinder { public: AP_RangeFinder_MaxsonarLV(); - int convert_raw_to_distance(int raw_value) { return raw_value * 2.54; } // read value from analog port and return distance in cm + int convert_raw_to_distance(int _raw_value) { return _raw_value * 2.54; } // read value from analog port and return distance in cm }; #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h index 07470a680c..9ee93f6674 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarXL.h @@ -10,6 +10,6 @@ class AP_RangeFinder_MaxsonarXL : public RangeFinder { public: AP_RangeFinder_MaxsonarXL(); - int convert_raw_to_distance(int raw_value) { return raw_value; } // read value from analog port and return distance in cm + int convert_raw_to_distance(int _raw_value) { return _raw_value; } // read value from analog port and return distance in cm }; #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h b/libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h index ffc1379b3b..7252a60553 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SharpGP2Y.h @@ -10,7 +10,7 @@ class AP_RangeFinder_SharpGP2Y : public RangeFinder { public: AP_RangeFinder_SharpGP2Y(); - int convert_raw_to_distance(int raw_value) { if( raw_value == 0 ) return max_distance; else return 14500/raw_value; } // read value from analog port and return distance in cm + int convert_raw_to_distance(int _raw_value) { if( _raw_value == 0 ) return max_distance; else return 14500/_raw_value; } // read value from analog port and return distance in cm }; #endif diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 2153740ba9..ac5dc17f96 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -17,7 +17,10 @@ #include "RangeFinder.h" // Constructor ///////////////////////////////////////////////////////////////// -RangeFinder::RangeFinder() : _num_averages(AP_RANGEFINDER_NUM_AVERAGES), _ap_adc(NULL), _history_ptr(0) +RangeFinder::RangeFinder() : + _ap_adc(NULL), + _num_averages(AP_RANGEFINDER_NUM_AVERAGES), + _history_ptr(0) { } @@ -94,4 +97,4 @@ int RangeFinder::read() // return distance return distance; -} \ No newline at end of file +} diff --git a/libraries/AP_RangeFinder/RangeFinder.h b/libraries/AP_RangeFinder/RangeFinder.h index 4ea57ede73..660629df8f 100644 --- a/libraries/AP_RangeFinder/RangeFinder.h +++ b/libraries/AP_RangeFinder/RangeFinder.h @@ -27,9 +27,9 @@ class RangeFinder RangeFinder(); // constructor int _analogPort; // the port to which the sensor is connected AP_ADC *_ap_adc; // pointer to AP_ADC used for pitot tube - int _history_ptr; // pointer to the most recent entry in the history table int _history[AP_RANGEFINDER_NUM_AVERAGES]; // history of recent distances used for filtering int _num_averages; // filter will return average of this many historic values (must be < AP_RANGEFINDER_NUM_AVERAGES) + int _history_ptr; // pointer to the most recent entry in the history table public: int raw_value; // raw value from the sensor int distance; // distance in cm @@ -40,7 +40,7 @@ class RangeFinder virtual void init(int analogPort, AP_ADC *adc = (AP_ADC*)NULL); virtual void set_orientation(int x, int y, int z); virtual void set_filter(int num_averages) { _num_averages = num_averages; } // allows control of amount of filtering done - virtual int convert_raw_to_distance(int raw_value) { return raw_value; } // function that each child class should override to convert voltage to distance + virtual int convert_raw_to_distance(int _raw_value) { return _raw_value; } // function that each child class should override to convert voltage to distance virtual int read(); // read value from sensor and return distance in cm }; #endif diff --git a/libraries/AP_RangeFinder/examples/AP_RangeFinder_test/AP_RangeFinder_test.pde b/libraries/AP_RangeFinder/examples/AP_RangeFinder_test/AP_RangeFinder_test.pde index 746a67fb4c..9aac4160c4 100644 --- a/libraries/AP_RangeFinder/examples/AP_RangeFinder_test/AP_RangeFinder_test.pde +++ b/libraries/AP_RangeFinder/examples/AP_RangeFinder_test/AP_RangeFinder_test.pde @@ -27,7 +27,6 @@ void setup() void loop() { - int i = 0; Serial.print("dist:"); Serial.print(aRF.read()); Serial.print("\traw:"); diff --git a/libraries/FastSerial/FastSerial.cpp b/libraries/FastSerial/FastSerial.cpp index b4c1cf9cbb..3e91a2f2da 100644 --- a/libraries/FastSerial/FastSerial.cpp +++ b/libraries/FastSerial/FastSerial.cpp @@ -189,7 +189,7 @@ void FastSerial::flush(void) void FastSerial::write(uint8_t c) { - int16_t i; + uint16_t i; if (!_open) // drop bytes if not open return; diff --git a/libraries/FastSerial/FastSerial.h b/libraries/FastSerial/FastSerial.h index 7cc62f4b32..267372c138 100644 --- a/libraries/FastSerial/FastSerial.h +++ b/libraries/FastSerial/FastSerial.h @@ -156,9 +156,10 @@ private: volatile uint8_t * const _ucsrb; // register magic numbers + const uint8_t _u2x; const uint8_t _portEnableBits; ///< rx, tx and rx interrupt enables const uint8_t _portTxBits; ///< tx data and completion interrupt enables - const uint8_t _u2x; + // ring buffers Buffer * const _rxBuffer; @@ -203,7 +204,7 @@ extern FastSerial::Buffer __FastSerial__txBuffer[]; ISR(_RXVECTOR, ISR_BLOCK) \ { \ uint8_t c; \ - int16_t i; \ + uint16_t i; \ \ /* read the byte as quickly as possible */ \ c = _UDR; \ diff --git a/libraries/FastSerial/vprintf.cpp b/libraries/FastSerial/vprintf.cpp index 3c83fe339a..b290e86baf 100644 --- a/libraries/FastSerial/vprintf.cpp +++ b/libraries/FastSerial/vprintf.cpp @@ -374,7 +374,7 @@ BetterStream::_vprintf (unsigned char in_progmem, const char *fmt, va_list ap) goto str_lpad; case 'S': - pgmstring: + // pgmstring: // not yet used pnt = va_arg (ap, char *); size = strnlen_P (pnt, (flags & FL_PREC) ? prec : ~0); flags |= FL_PGMSTRING; diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index d0fac763ed..3042553f98 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -32,6 +32,8 @@ static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch) case MAVLINK_COMM_1: mavlink_comm_1_port->write(ch); break; + default: + break; } } @@ -51,6 +53,8 @@ static inline uint8_t comm_receive_ch(mavlink_channel_t chan) case MAVLINK_COMM_1: data = mavlink_comm_1_port->read(); break; + default: + break; } return data; } @@ -69,6 +73,8 @@ static inline uint16_t comm_get_available(mavlink_channel_t chan) case MAVLINK_COMM_1: bytes = mavlink_comm_1_port->available(); break; + default: + break; } return bytes; } diff --git a/libraries/GCS_MAVLink/include/protocol.h b/libraries/GCS_MAVLink/include/protocol.h index c6aace92e8..09409fcd4f 100644 --- a/libraries/GCS_MAVLink/include/protocol.h +++ b/libraries/GCS_MAVLink/include/protocol.h @@ -827,7 +827,7 @@ static inline uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t p // First pack everything we can into the current 'open' byte //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 //FIXME - if (bits_remain <= (8 - i_bit_index)) + if (bits_remain <= uint16_t(8 - i_bit_index)) { // Enough space curr_bits_n = bits_remain;