mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
cf8ce867e6
irlock_center_x_pos calculates the lateral x position of the marker in cm. relative to the quad irlock_x_pos_to_latlon rotates the frame based x position to latitude/longtitude based coordinates same case for the y position add get_angle_to_target method get_angle_to_target replaces pixel to position calculations Also removed ahrs reference (now in AC_PrecLand lib), unused references to orb and commented out parameter declaration reduce max objects to 5 remove ahrs reference add timeout return true if new sample found bug fix get_angle_to_target remove unused get_frame
86 lines
2.2 KiB
C++
86 lines
2.2 KiB
C++
/*
|
|
This program is free software: you can redistribute it and/or modify
|
|
it under the terms of the GNU General Public License as published by
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
(at your option) any later version.
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
GNU General Public License for more details.
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
|
|
/*
|
|
* AP_IRLock_PX4.cpp
|
|
*
|
|
* Created on: Nov 16, 2014
|
|
* Author: MLandes
|
|
*/
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
#include "AP_IRLock_PX4.h"
|
|
|
|
#include <fcntl.h>
|
|
#include <unistd.h>
|
|
|
|
#include "AP_HAL.h"
|
|
#include "drivers/drv_irlock.h"
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
AP_IRLock_PX4::AP_IRLock_PX4() :
|
|
_fd(0),
|
|
_last_timestamp(0)
|
|
{}
|
|
|
|
void AP_IRLock_PX4::init()
|
|
{
|
|
_fd = open(IRLOCK0_DEVICE_PATH, O_RDONLY);
|
|
if (_fd < 0) {
|
|
hal.console->printf("Unable to open " IRLOCK0_DEVICE_PATH "\n");
|
|
return;
|
|
}
|
|
|
|
_flags.healthy = true;
|
|
}
|
|
|
|
// retrieve latest sensor data - returns true if new data is available
|
|
bool AP_IRLock_PX4::update()
|
|
{
|
|
// return immediately if not healthy
|
|
if (!_flags.healthy) {
|
|
return false;
|
|
}
|
|
|
|
// read position of all objects
|
|
struct irlock_s report;
|
|
uint16_t count = 0;
|
|
while(::read(_fd, &report, sizeof(struct irlock_s)) == sizeof(struct irlock_s) && report.timestamp >_last_timestamp) {
|
|
_current_frame[count].signature = report.signature;
|
|
_current_frame[count].center_x = report.center_x;
|
|
_current_frame[count].center_y = report.center_y;
|
|
_current_frame[count].width = report.width;
|
|
_current_frame[count].height = report.height;
|
|
|
|
count++;
|
|
_last_timestamp = report.timestamp;
|
|
_last_update = hal.scheduler->millis();
|
|
}
|
|
|
|
// update num_blocks and implement timeout
|
|
if (count > 0) {
|
|
_num_blocks = count;
|
|
} else if ((hal.scheduler->millis() - _last_update) > IRLOCK_TIMEOUT_MS) {
|
|
_num_blocks = 0;
|
|
}
|
|
|
|
// return true if new data found
|
|
return (_num_blocks > 0);
|
|
}
|
|
|
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
|