Browse Source

AC_PrecLand: add override and fix formatting

master
Randy Mackay 8 years ago
parent
commit
bdf49c8a01
  1. 12
      libraries/AC_PrecLand/AC_PrecLand_Companion.h
  2. 10
      libraries/AC_PrecLand/AC_PrecLand_IRLock.h
  3. 10
      libraries/AC_PrecLand/AC_PrecLand_SITL.h
  4. 10
      libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h

12
libraries/AC_PrecLand/AC_PrecLand_Companion.h

@ -16,26 +16,26 @@ public: @@ -16,26 +16,26 @@ public:
AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state);
// perform any required initialisation of backend
void init();
void init() override;
// retrieve updates from sensor
void update();
void update() override;
// provides a unit vector towards the target in body frame
// returns same as have_los_meas()
bool get_los_body(Vector3f& ret);
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms();
uint32_t los_meas_time_ms() override;
// return true if there is a valid los measurement available
bool have_los_meas();
bool have_los_meas() override;
// returns distance to target in meters (0 means distance is not known)
float distance_to_target() override;
// parses a mavlink message from the companion computer
void handle_msg(mavlink_message_t* msg);
void handle_msg(mavlink_message_t* msg) override;
private:
uint64_t _timestamp_us; // timestamp from message

10
libraries/AC_PrecLand/AC_PrecLand_IRLock.h

@ -25,20 +25,20 @@ public: @@ -25,20 +25,20 @@ public:
AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state);
// perform any required initialisation of backend
void init();
void init() override;
// retrieve updates from sensor
void update();
void update() override;
// provides a unit vector towards the target in body frame
// returns same as have_los_meas()
bool get_los_body(Vector3f& ret);
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms();
uint32_t los_meas_time_ms() override;
// return true if there is a valid los measurement available
bool have_los_meas();
bool have_los_meas() override;
private:
AP_IRLock_I2C irlock;

10
libraries/AC_PrecLand/AC_PrecLand_SITL.h

@ -17,20 +17,20 @@ public: @@ -17,20 +17,20 @@ public:
AC_PrecLand_SITL(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state);
// perform any required initialisation of backend
void init();
void init() override;
// retrieve updates from sensor
void update();
void update() override;
// provides a unit vector towards the target in body frame
// returns same as have_los_meas()
bool get_los_body(Vector3f& ret);
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms() { return _los_meas_time_ms; }
uint32_t los_meas_time_ms() override { return _los_meas_time_ms; }
// return true if there is a valid los measurement available
bool have_los_meas();
bool have_los_meas() override;
private:

10
libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h

@ -19,20 +19,20 @@ public: @@ -19,20 +19,20 @@ public:
AC_PrecLand_SITL_Gazebo(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state);
// perform any required initialisation of backend
void init();
void init() override;
// retrieve updates from sensor
void update();
void update() override;
// provides a unit vector towards the target in body frame
// returns same as have_los_meas()
bool get_los_body(Vector3f& ret);
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms();
uint32_t los_meas_time_ms() override;
// return true if there is a valid los measurement available
bool have_los_meas();
bool have_los_meas() override;
private:
AP_IRLock_SITL irlock;

Loading…
Cancel
Save