ardupilot/libraries/AP_IRLock/IRLock.cpp
Pierre Kancir 42cc9c755a AP_IRLock: add SITL IRLock
AP_IRLock: simplify include

AP_IRLock: reduce scope of gazebo irlock_paquet

AP_IRLock: add z pos for IRLock SITL, set to 1.0 for pixycam

AP_IRLock: remove unused target size and get_angle_to_target_rad function
2019-03-01 20:28:22 +11:00

26 lines
533 B
C++

/*
* IRLock.cpp
*
* Created on: Nov 12, 2014
* Author: MLandes
*/
#include "IRLock.h"
// 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 (!_flags.healthy) {
return false;
}
// use data from first (largest) object
ret.x = -_target_info.pos_y;
ret.y = _target_info.pos_x;
ret.z = _target_info.pos_z;
ret /= ret.length();
return true;
}