diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 02dc3566126f11..f25f79adfb22e8 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -102,7 +102,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(compass_accumulate, 100, 100), SCHED_TASK(barometer_accumulate, 50, 90), #if PRECISION_LANDING == ENABLED - SCHED_TASK(update_precland, 50, 50), + SCHED_TASK(update_precland, 400, 50), #endif #if FRAME_CONFIG == HELI_FRAME SCHED_TASK(check_dynamic_flight, 50, 75), @@ -428,6 +428,11 @@ void Copter::twentyfive_hz_logging() DataFlash.Log_Write_IMU(ins); } #endif + +#if PRECISION_LANDING == ENABLED + // log output + Log_Write_Precland(); +#endif } void Copter::dataflash_periodic(void) diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index 4b4592ad052328..769bf69bc03965 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -15,16 +15,15 @@ void Copter::init_precland() void Copter::update_precland() { - float final_alt = current_loc.alt; + int32_t height_above_ground_cm = current_loc.alt; - // use range finder altitude if it is valid + // use range finder altitude if it is valid, else try to get terrain alt if (rangefinder_alt_ok()) { - final_alt = rangefinder_state.alt_cm; + height_above_ground_cm = rangefinder_state.alt_cm; + } else if (terrain_use()) { + current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, height_above_ground_cm); } - copter.precland.update(final_alt); - - // log output - Log_Write_Precland(); + copter.precland.update(height_above_ground_cm); } #endif diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 1ba2a8ec18f91c..c2cbf0f00716a5 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -83,12 +83,19 @@ void AC_PrecLand::init() void AC_PrecLand::update(float alt_above_terrain_cm) { // run backend update - if (_backend != NULL) { + if (_backend != NULL && _enabled) { // read from sensor _backend->update(); - - // calculate angles to target and position estimate - calc_angles_and_pos(alt_above_terrain_cm); + + if (_backend->have_los_meas() && _backend->los_meas_time_ms() != _last_backend_los_meas_ms) { + // we have a new, unique los measurement + _last_backend_los_meas_ms = _backend->los_meas_time_ms(); + + Vector3f target_vec_unit_body; + _backend->get_los_body(target_vec_unit_body); + + calc_angles_and_pos(target_vec_unit_body, alt_above_terrain_cm); + } } } @@ -126,55 +133,23 @@ bool AC_PrecLand::get_target_velocity_relative(Vector3f& ret) // raw sensor angles stored in _angle_to_target (might be in earth frame, or maybe body frame) // earth-frame angles stored in _ef_angle_to_target // position estimate is stored in _target_pos -void AC_PrecLand::calc_angles_and_pos(float alt_above_terrain_cm) +void AC_PrecLand::calc_angles_and_pos(const Vector3f& target_vec_unit_body, float alt_above_terrain_cm) { - // exit immediately if not enabled - if (_backend == NULL) { - return; - } - - // get angles to target from backend - if (!_backend->get_angle_to_target(_angle_to_target.x, _angle_to_target.y)) { - return; - } - - _angle_to_target.x = -_angle_to_target.x; - _angle_to_target.y = -_angle_to_target.y; - - // compensate for delay - _angle_to_target.x -= _ahrs.get_gyro().x*4.0e-2f; - _angle_to_target.y -= _ahrs.get_gyro().y*4.0e-2f; - - Vector3f target_vec_ned; - - if (_angle_to_target.is_zero()) { - target_vec_ned = Vector3f(0.0f,0.0f,1.0f); - } else { - float theta = _angle_to_target.length(); - Vector3f axis = Vector3f(_angle_to_target.x, _angle_to_target.y, 0.0f)/theta; - float sin_theta = sinf(theta); - float cos_theta = cosf(theta); - - target_vec_ned.x = axis.y*sin_theta; - target_vec_ned.y = -axis.x*sin_theta; - target_vec_ned.z = cos_theta; - } - // rotate into NED frame - target_vec_ned = _ahrs.get_rotation_body_to_ned()*target_vec_ned; + Vector3f target_vec_unit_ned = _ahrs.get_rotation_body_to_ned()*target_vec_unit_body; // extract the angles to target (logging only) - _ef_angle_to_target.x = atan2f(target_vec_ned.z,target_vec_ned.x); - _ef_angle_to_target.y = atan2f(target_vec_ned.z,target_vec_ned.y); + _angle_to_target.x = atan2f(-target_vec_unit_body.y, target_vec_unit_body.z); + _angle_to_target.y = atan2f( target_vec_unit_body.x, target_vec_unit_body.z); + _ef_angle_to_target.x = atan2f(-target_vec_unit_ned.y, target_vec_unit_ned.z); + _ef_angle_to_target.y = atan2f( target_vec_unit_ned.x, target_vec_unit_ned.z); - // ensure that the angle to target is no more than 70 degrees - if (target_vec_ned.z > 0.26f) { + if (target_vec_unit_ned.z > 0.0f) { // get current altitude (constrained to be positive) float alt = MAX(alt_above_terrain_cm, 0.0f); - float dist = alt/target_vec_ned.z; - // - _target_pos_rel.x = target_vec_ned.x*dist; - _target_pos_rel.y = target_vec_ned.y*dist; + float dist = alt/target_vec_unit_ned.z; + _target_pos_rel.x = target_vec_unit_ned.x*dist; + _target_pos_rel.y = target_vec_unit_ned.y*dist; _target_pos_rel.z = alt; // not used _target_pos = _inav.get_position()+_target_pos_rel; diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 12ab889167f50f..5be6d4390c5d6f 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -83,7 +83,7 @@ class AC_PrecLand // angles stored in _angle_to_target // earth-frame angles stored in _ef_angle_to_target // position estimate is stored in _target_pos - void calc_angles_and_pos(float alt_above_terrain_cm); + void calc_angles_and_pos(const Vector3f& target_vec_unit_body, float alt_above_terrain_cm); // returns enabled parameter as an behaviour enum PrecLandBehaviour get_behaviour() const { return (enum PrecLandBehaviour)(_enabled.get()); } @@ -97,6 +97,7 @@ class AC_PrecLand AP_Int8 _type; // precision landing controller type uint32_t _last_update_ms; // epoch time in millisecond when update is called + uint32_t _last_backend_los_meas_ms; // output from sensor (stored for logging) Vector2f _angle_to_target; // last raw sensor angle to target diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index d8b7aeefd18360..6cdc422417820b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -10,7 +10,6 @@ class AC_PrecLand_Backend { public: - // Constructor AC_PrecLand_Backend(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : _frontend(frontend), @@ -19,26 +18,26 @@ class AC_PrecLand_Backend // destructor virtual ~AC_PrecLand_Backend() {} - // init - perform any required initialisation of backend controller + // perform any required initialisation of backend virtual void init() = 0; - // update - give chance to driver to get updates from sensor - // returns true if new data available - virtual bool update() = 0; - // what frame of reference is our sensor reporting in? - virtual MAV_FRAME get_frame_of_reference() = 0; - - // get_angle_to_target - returns angles (in radians) to target - // returns true if angles are available, false if not (i.e. no target) - // x_angle_rad : roll direction, positive = target is to right (looking down) - // y_angle_rad : pitch direction, postiive = target is forward (looking down) - virtual bool get_angle_to_target(float &x_angle_rad, float &y_angle_rad) = 0; - - // handle_msg - parses a mavlink message from the companion computer + // retrieve updates from sensor + virtual void update() = 0; + + // provides a unit vector towards the target in body frame + // returns same as have_los_meas() + virtual bool get_los_body(Vector3f& dir_body) = 0; + + // returns system time in milliseconds of last los measurement + virtual uint32_t los_meas_time_ms() = 0; + + // return true if there is a valid los measurement available + virtual bool have_los_meas() = 0; + + // parses a mavlink message from the companion computer virtual void handle_msg(mavlink_message_t* msg) = 0; protected: - const AC_PrecLand& _frontend; // reference to precision landing front end AC_PrecLand::precland_state &_state; // reference to this instances state }; diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index 1498dd7fd6c421..61f3accec442c5 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -7,52 +7,47 @@ extern const AP_HAL::HAL& hal; // Constructor AC_PrecLand_Companion::AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), - _frame(MAV_FRAME_BODY_NED), _distance_to_target(0.0f), _timestamp_us(0), - _new_estimate(false) + _have_los_meas(false) { } -// init - perform initialisation of this backend +// perform any required initialisation of backend void AC_PrecLand_Companion::init() { // set healthy _state.healthy = true; - _new_estimate = false; + _have_los_meas = false; } -// update - give chance to driver to get updates from sensor -// returns true if new data available -bool AC_PrecLand_Companion::update() +// retrieve updates from sensor +void AC_PrecLand_Companion::update() { - // Mavlink commands are received asynchronous so all new data is processed by handle_msg() - return _new_estimate; + _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000; } -MAV_FRAME AC_PrecLand_Companion::get_frame_of_reference() -{ - return _frame; -} - -// get_angle_to_target - returns angles (in radians) to target -// returns true if angles are available, false if not (i.e. no target) -// x_angle_rad : roll direction, positive = target is to right (looking down) -// y_angle_rad : pitch direction, postiive = target is forward (looking down) -bool AC_PrecLand_Companion::get_angle_to_target(float &x_angle_rad, float &y_angle_rad) -{ - if (_new_estimate){ - x_angle_rad = _angle_to_target.x; - y_angle_rad = _angle_to_target.y; - - // reset and wait for new data - _new_estimate = false; +// provides a unit vector towards the target in body frame +// returns same as have_los_meas() +bool AC_PrecLand_Companion::get_los_body(Vector3f& ret) { + if (have_los_meas()) { + ret = _los_meas_body; return true; } - return false; } +// returns system time in milliseconds of last los measurement +uint32_t AC_PrecLand_Companion::los_meas_time_ms() { + return _los_meas_time_ms; +} + +// return true if there is a valid los measurement available +bool AC_PrecLand_Companion::have_los_meas() +{ + return _have_los_meas; +} + void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg) { // parse mavlink message @@ -60,10 +55,12 @@ void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg) mavlink_msg_landing_target_decode(msg, &packet); _timestamp_us = packet.time_usec; - _frame = (MAV_FRAME) packet.frame; - _angle_to_target.x = packet.angle_x; - _angle_to_target.y = packet.angle_y; _distance_to_target = packet.distance; - _state.healthy = true; - _new_estimate = true; + + // compute unit vector towards target + _los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f); + _los_meas_body /= _los_meas_body.length(); + + _los_meas_time_ms = AP_HAL::millis(); + _have_los_meas = true; } diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 7048d5605b7a9d..9c108f90e19eb4 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -13,34 +13,33 @@ class AC_PrecLand_Companion : public AC_PrecLand_Backend { public: - // Constructor AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); - - // init - perform any required initialisation of backend controller + + // perform any required initialisation of backend void init(); - // update - give chance to driver to get updates from sensor - // returns true if new data available - bool update(); - // what frame of reference is our sensor reporting in? - MAV_FRAME get_frame_of_reference(); - - // get_angle_to_target - returns angles (in radians) to target - // returns true if angles are available, false if not (i.e. no target) - // x_angle_rad : roll direction, positive = target is to right (looking down) - // y_angle_rad : pitch direction, postiive = target is forward (looking down) - bool get_angle_to_target(float &x_angle_rad, float &y_angle_rad); - - // handle_msg - parses a mavlink message from the companion computer + // retrieve updates from sensor + void update(); + + // provides a unit vector towards the target in body frame + // returns same as have_los_meas() + bool get_los_body(Vector3f& ret); + + // returns system time in milliseconds of last los measurement + uint32_t los_meas_time_ms(); + + // return true if there is a valid los measurement available + bool have_los_meas(); + + // parses a mavlink message from the companion computer void handle_msg(mavlink_message_t* msg); private: - - // output from camera - MAV_FRAME _frame; // what frame of reference is our sensor reporting in? - Vector2f _angle_to_target; // last angle to target + uint64_t _timestamp_us; // timestamp from message float _distance_to_target; // distance from the camera to target in meters - uint64_t _timestamp_us; // timestamp when the image was captured(synced via UAVCAN) - bool _new_estimate; // true if new data from the camera has been received + + Vector3f _los_meas_body; // unit vector in body frame pointing towards target + bool _have_los_meas; // true if there is a valid measurement from the camera + uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured }; diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index 9666aa44cfc57a..47124e10be89c9 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -10,7 +10,9 @@ extern const AP_HAL::HAL& hal; // Constructor AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) : AC_PrecLand_Backend(frontend, state), - irlock() + irlock(), + _have_los_meas(false), + _los_meas_time_ms(0) { } @@ -18,25 +20,43 @@ AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand: void AC_PrecLand_IRLock::init() { irlock.init(); - - // set healthy - _state.healthy = irlock.healthy(); } // update - give chance to driver to get updates from sensor -bool AC_PrecLand_IRLock::update() +void AC_PrecLand_IRLock::update() { + // update health + _state.healthy = irlock.healthy(); + // get new sensor data - return (irlock.update()); + irlock.update(); + + if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas_time_ms) { + irlock.get_unit_vector_body(_los_meas_body); + _have_los_meas = true; + _los_meas_time_ms = irlock.last_update_ms(); + } + _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000; } -// get_angle_to_target - returns body frame angles (in radians) to target -// returns true if angles are available, false if not (i.e. no target) -// x_angle_rad : body-frame roll direction, positive = target is to right (looking down) -// y_angle_rad : body-frame pitch direction, postiive = target is forward (looking down) -bool AC_PrecLand_IRLock::get_angle_to_target(float &x_angle_rad, float &y_angle_rad) -{ - return irlock.get_angle_to_target(x_angle_rad, y_angle_rad); +// provides a unit vector towards the target in body frame +// returns same as have_los_meas() +bool AC_PrecLand_IRLock::get_los_body(Vector3f& ret) { + if (have_los_meas()) { + ret = _los_meas_body; + return true; + } + return false; +} + +// returns system time in milliseconds of last los measurement +uint32_t AC_PrecLand_IRLock::los_meas_time_ms() { + return _los_meas_time_ms; +} + +// return true if there is a valid los measurement available +bool AC_PrecLand_IRLock::have_los_meas() { + return _have_los_meas; } #endif // PX4 diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index 62e1fbddc1ecd5..2d792bf86a0eb5 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -20,27 +20,31 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend // Constructor AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); - - // init - perform any required initialisation of backend controller + + // perform any required initialisation of backend void init(); - // update - give chance to driver to get updates from sensor - // returns true if new data available - bool update(); - // IRLock is hard-mounted to the frame of the vehicle, so it will always be in body-frame - MAV_FRAME get_frame_of_reference() { return MAV_FRAME_BODY_NED; } - - // get_angle_to_target - returns body frame angles (in radians) to target - // returns true if angles are available, false if not (i.e. no target) - // x_angle_rad : body-frame roll direction, positive = target is to right (looking down) - // y_angle_rad : body-frame pitch direction, postiive = target is forward (looking down) - bool get_angle_to_target(float &x_angle_rad, float &y_angle_rad); - - // handle_msg - parses a mavlink message from the companion computer - void handle_msg(mavlink_message_t* msg) { /* do nothing */ } + // retrieve updates from sensor + void update(); + + // provides a unit vector towards the target in body frame + // returns same as have_los_meas() + bool get_los_body(Vector3f& ret); + + // returns system time in milliseconds of last los measurement + uint32_t los_meas_time_ms(); + + // return true if there is a valid los measurement available + bool have_los_meas(); + + // parses a mavlink message from the companion computer + void handle_msg(mavlink_message_t* msg) {}; private: AP_IRLock_PX4 irlock; - + + Vector3f _los_meas_body; // unit vector in body frame pointing towards target + bool _have_los_meas; // true if there is a valid measurement from the camera + uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured }; #endif diff --git a/libraries/AP_IRLock/AP_IRLock_PX4.cpp b/libraries/AP_IRLock/AP_IRLock_PX4.cpp index 24bc95d2b995bb..63454ef56bd663 100644 --- a/libraries/AP_IRLock/AP_IRLock_PX4.cpp +++ b/libraries/AP_IRLock/AP_IRLock_PX4.cpp @@ -31,8 +31,7 @@ extern const AP_HAL::HAL& hal; AP_IRLock_PX4::AP_IRLock_PX4() : - _fd(0), - _last_timestamp(0) + _fd(0) {} void AP_IRLock_PX4::init() @@ -55,29 +54,23 @@ bool AP_IRLock_PX4::update() } // read position of all objects + bool new_data = false; struct irlock_s report; - uint16_t count = 0; - while(::read(_fd, &report, sizeof(struct irlock_s)) == sizeof(struct irlock_s) && report.timestamp >_last_timestamp) { - _target_info[count].timestamp = report.timestamp; - _target_info[count].target_num = report.target_num; - _target_info[count].angle_x = report.angle_x; - _target_info[count].angle_y = report.angle_y; - _target_info[count].size_x = report.size_x; - _target_info[count].size_y = report.size_y; - count++; - _last_timestamp = report.timestamp; - _last_update = AP_HAL::millis(); - } - - // update num_blocks and implement timeout - if (count > 0) { - _num_targets = count; - } else if ((AP_HAL::millis() - _last_update) > IRLOCK_TIMEOUT_MS) { - _num_targets = 0; + while(::read(_fd, &report, sizeof(struct irlock_s)) == sizeof(struct irlock_s)) { + new_data = true; + _num_targets = report.num_targets; + for (uint8_t i=0; i 0); + return new_data; } #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_IRLock/AP_IRLock_PX4.h b/libraries/AP_IRLock/AP_IRLock_PX4.h index f9168dd53e5984..e78c1dac4b64bb 100644 --- a/libraries/AP_IRLock/AP_IRLock_PX4.h +++ b/libraries/AP_IRLock/AP_IRLock_PX4.h @@ -21,5 +21,4 @@ class AP_IRLock_PX4 : public IRLock private: int _fd; - uint64_t _last_timestamp; }; diff --git a/libraries/AP_IRLock/IRLock.cpp b/libraries/AP_IRLock/IRLock.cpp index be90300479bea1..99b2d9c1442763 100644 --- a/libraries/AP_IRLock/IRLock.cpp +++ b/libraries/AP_IRLock/IRLock.cpp @@ -9,7 +9,7 @@ // default constructor IRLock::IRLock() : - _last_update(0), + _last_update_ms(0), _num_targets(0) { // clear target info @@ -21,17 +21,34 @@ IRLock::IRLock() : IRLock::~IRLock() {} -// get_angle_to_target - retrieve body frame x and y angles (in radians) to target -// returns true if angles are available, false if not (i.e. no target) -bool IRLock::get_angle_to_target(float &x_angle_rad, float &y_angle_rad) const +// retrieve body frame x and y angles (in radians) to target +// returns true if data is available +bool IRLock::get_angle_to_target_rad(float &x_angle_rad, float &y_angle_rad) const { // return false if we have no target if (_num_targets == 0) { return false; } - // use data from first object - x_angle_rad = _target_info[0].angle_x; - y_angle_rad = _target_info[0].angle_y; + // use data from first (largest) object + x_angle_rad = atanf(_target_info[0].pos_x); + y_angle_rad = atanf(_target_info[0].pos_y); return true; } + +// retrieve body frame unit vector in direction of target +// returns true if data is available +bool IRLock::get_unit_vector_body(Vector3f& ret) const +{ + // return false if we have no target + if (_num_targets == 0) { + return false; + } + + // use data from first (largest) object + ret.x = -_target_info[0].pos_y; + ret.y = _target_info[0].pos_x; + ret.z = 1.0f; + ret /= ret.length(); + return true; +} \ No newline at end of file diff --git a/libraries/AP_IRLock/IRLock.h b/libraries/AP_IRLock/IRLock.h index d134ebf1842ec4..4608cc0921db20 100644 --- a/libraries/AP_IRLock/IRLock.h +++ b/libraries/AP_IRLock/IRLock.h @@ -24,7 +24,6 @@ #include #define IRLOCK_MAX_TARGETS 5 // max number of targets that can be detected by IR-LOCK sensor (should match PX4Firmware's irlock driver's IRLOCK_OBJECTS_MAX) -#define IRLOCK_TIMEOUT_MS 100 // target info times out after 0.1 seconds class IRLock { @@ -40,7 +39,7 @@ class IRLock bool healthy() const { return _flags.healthy; } // timestamp of most recent data read from the sensor - uint32_t last_update() const { return _last_update; } + uint32_t last_update_ms() const { return _last_update_ms; } // returns the number of blocks in the current frame size_t num_targets() const { return _num_targets; } @@ -48,9 +47,14 @@ class IRLock // retrieve latest sensor data - returns true if new data is available virtual bool update() = 0; - // get_angle_to_target - retrieve body frame x and y angles (in radians) to target - // returns true if angles are available, false if not (i.e. no target) - bool get_angle_to_target(float &x_angle_rad, float &y_angle_rad) const; + // retrieve body frame x and y angles (in radians) to target + // returns true if data is available + bool get_angle_to_target_rad(float &x_angle_rad, float &y_angle_rad) const; + + // retrieve body frame unit vector in direction of target + // returns true if data is available + bool get_unit_vector_body(Vector3f& ret) const; + protected: struct AP_IRLock_Flags { @@ -58,17 +62,16 @@ class IRLock } _flags; // internals - uint32_t _last_update; + uint32_t _last_update_ms; uint16_t _num_targets; // irlock_target_info is a duplicate of the PX4Firmware irlock_s structure typedef struct { - uint64_t timestamp; // time target was seen in microseconds since system start - uint16_t target_num; // target number prioritised by size (largest is 0) - float angle_x; // x-axis angle in radians from center of image to center of target - float angle_y; // y-axis angle in radians from center of image to center of target - float size_x; // size in radians of target along x-axis - float size_y; // size in radians of target along y-axis + uint64_t timestamp; // microseconds since system start + float pos_x; // x-axis distance from center of image to center of target in units of tan(theta) + float pos_y; // y-axis distance from center of image to center of target in units of tan(theta) + float size_x; // size of target along x-axis in units of tan(theta) + float size_y; // size of target along y-axis in units of tan(theta) } irlock_target_info; irlock_target_info _target_info[IRLOCK_MAX_TARGETS]; diff --git a/modules/PX4Firmware b/modules/PX4Firmware index 4a1d6880549f95..c2d66c8a1cd27f 160000 --- a/modules/PX4Firmware +++ b/modules/PX4Firmware @@ -1 +1 @@ -Subproject commit 4a1d6880549f95858686c0faa770bd1c644779dd +Subproject commit c2d66c8a1cd27fb91ee263fe59c764c635531ae7