mirror of https://github.com/ArduPilot/ardupilot
AC_Precland: remove unused _timestamp_us
This commit is contained in:
parent
b749756c29
commit
9513bbe85f
|
@ -48,7 +48,6 @@ void AC_PrecLand_Companion::handle_msg(const mavlink_message_t &msg)
|
||||||
__mavlink_landing_target_t packet;
|
__mavlink_landing_target_t packet;
|
||||||
mavlink_msg_landing_target_decode(&msg, &packet);
|
mavlink_msg_landing_target_decode(&msg, &packet);
|
||||||
|
|
||||||
_timestamp_us = packet.time_usec;
|
|
||||||
_distance_to_target = packet.distance;
|
_distance_to_target = packet.distance;
|
||||||
|
|
||||||
// compute unit vector towards target
|
// compute unit vector towards target
|
||||||
|
|
|
@ -39,7 +39,6 @@ public:
|
||||||
void handle_msg(const mavlink_message_t &msg) override;
|
void handle_msg(const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint64_t _timestamp_us; // timestamp from message
|
|
||||||
float _distance_to_target; // distance from the camera to target in meters
|
float _distance_to_target; // distance from the camera to target in meters
|
||||||
|
|
||||||
Vector3f _los_meas_body; // unit vector in body frame pointing towards target
|
Vector3f _los_meas_body; // unit vector in body frame pointing towards target
|
||||||
|
|
Loading…
Reference in New Issue