mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Proximity: compiler warning fixes
In file included from ../../libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp:30: ../../libraries/AP_Proximity/AP_Proximity_RPLidarA2.h:88:10: warning: private field '_payload_data' is not used [-Wunused-private-field] bool _payload_data; ^ ../../libraries/AP_Proximity/AP_Proximity_RPLidarA2.h:91:10: warning: private field '_skip' is not used [-Wunused-private-field] bool _skip; ^ ../../libraries/AP_Proximity/AP_Proximity_RPLidarA2.h:92:10: warning: private field '_rp_reset' is not used [-Wunused-private-field] bool _rp_reset; ^ ../../libraries/AP_Proximity/AP_Proximity_RPLidarA2.h:95:13: warning: private field '_element_len' is not used [-Wunused-private-field] uint8_t _element_len[2]; ^ ../../libraries/AP_Proximity/AP_Proximity_RPLidarA2.h:96:13: warning: private field '_element_num' is not used [-Wunused-private-field] uint8_t _element_num; ^ 5 warnings generated.
This commit is contained in:
parent
1915244960
commit
e7d48977ba
@ -85,15 +85,10 @@ private:
|
||||
char _rp_systeminfo[63];
|
||||
bool _descriptor_data;
|
||||
bool _information_data;
|
||||
bool _payload_data;
|
||||
bool _resetted;
|
||||
bool _initialised;
|
||||
bool _skip;
|
||||
bool _rp_reset;
|
||||
bool _sector_initialised;
|
||||
|
||||
uint8_t _element_len[2];
|
||||
uint8_t _element_num;
|
||||
uint8_t _payload_length;
|
||||
uint8_t _cnt;
|
||||
uint8_t _sync_error ;
|
||||
|
Loading…
Reference in New Issue
Block a user