mirror of https://github.com/ArduPilot/ardupilot
SITL: correct compiler warning
In file included from ../../libraries/SITL/SIM_last_letter.cpp:19: ../../libraries/SITL/SIM_last_letter.h:74:17: warning: private field 'frame_str' is not used [-Wunused-private-field] const char *frame_str; SITL: correct compiler warning In file included from ../../libraries/SITL/SIM_Sprayer.cpp:19: ../../libraries/SITL/SIM_Sprayer.h:55:14: warning: private field 'start_time_us' is not used [-Wunused-private-field] uint64_t start_time_us; SITL: correct compiler warnings In file included from ../../libraries/SITL/SIM_Gripper_Servo.cpp:19: ../../libraries/SITL/SIM_Gripper_Servo.h:56:10: warning: private field 'zero_report_done' is not used [-Wunused-private-field] bool zero_report_done = false; SITL: correct compiler warnings In file included from ../../libraries/SITL/SIM_ADSB.cpp:19: ../../libraries/SITL/SIM_ADSB.h:49:28: warning: private field 'fdm' is not used [-Wunused-private-field] const struct sitl_fdm &fdm;
This commit is contained in:
parent
844ed611c6
commit
1915244960
|
@ -27,8 +27,7 @@ namespace SITL {
|
|||
|
||||
SITL *_sitl;
|
||||
|
||||
ADSB::ADSB(const struct sitl_fdm &_fdm, const char *_home_str) :
|
||||
fdm(_fdm)
|
||||
ADSB::ADSB(const struct sitl_fdm &_fdm, const char *_home_str)
|
||||
{
|
||||
float yaw_degrees;
|
||||
Aircraft::parse_home(_home_str, home, yaw_degrees);
|
||||
|
|
|
@ -46,7 +46,6 @@ public:
|
|||
void update(void);
|
||||
|
||||
private:
|
||||
const struct sitl_fdm &fdm;
|
||||
const char *target_address = "127.0.0.1";
|
||||
const uint16_t target_port = 5762;
|
||||
|
||||
|
|
|
@ -53,7 +53,6 @@ private:
|
|||
uint64_t last_update_us;
|
||||
|
||||
bool should_report();
|
||||
bool zero_report_done = false;
|
||||
|
||||
// dangle load from a string:
|
||||
const float string_length = 2.0f; // metres
|
||||
|
|
|
@ -52,7 +52,6 @@ private:
|
|||
|
||||
double capacity = 0.25; // litres
|
||||
|
||||
uint64_t start_time_us;
|
||||
uint64_t last_update_us;
|
||||
|
||||
bool should_report();
|
||||
|
|
|
@ -32,8 +32,7 @@ namespace SITL {
|
|||
last_letter::last_letter(const char *home_str, const char *_frame_str) :
|
||||
Aircraft(home_str, _frame_str),
|
||||
last_timestamp_us(0),
|
||||
sock(true),
|
||||
frame_str(_frame_str)
|
||||
sock(true)
|
||||
{
|
||||
// try to bind to a specific port so that if we restart ArduPilot
|
||||
// last_letter keeps sending us packets. Not strictly necessary but
|
||||
|
|
|
@ -70,8 +70,6 @@ private:
|
|||
|
||||
uint64_t last_timestamp_us;
|
||||
SocketAPM sock;
|
||||
|
||||
const char *frame_str;
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
|
Loading…
Reference in New Issue