mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_Linux: OpticalFlow_Onboard: follow coding style
- Remove commented out defines - Sort headers - Remove ifdef for HAL_BOARD_SUBTYPE_LINUX_BEBOP inside the same ifdef - Use AP_HAL::panic() instead of perror - AP_HAL::panic() message doesn't take a '\n' and there's no return statement after a call to this function - Fix pointer placement - Use pragma once - Don't initialize members to 0, it's already the default behavior of our custom allocator
This commit is contained in:
parent
ea89308d90
commit
83c50e12ca
@ -18,11 +18,9 @@
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "GPIO.h"
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
#include "OpticalFlow_Onboard.h"
|
||||
#include "CameraSensor_Mt9v117.h"
|
||||
#include "PWM_Sysfs.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <pthread.h>
|
||||
#include <sys/types.h>
|
||||
@ -31,9 +29,10 @@
|
||||
#include <unistd.h>
|
||||
#include <linux/v4l2-mediabus.h>
|
||||
|
||||
//#define OPTICALFLOW_ONBOARD_RECORD_VIDEO 1
|
||||
//#define OPTICALFLOW_ONBOARD_VIDEO_FILE "/data/ftp/internal_000/optflow.bin"
|
||||
//#define OPTICALFLOW_ONBOARD_RECORD_METADATAS 1
|
||||
#include "CameraSensor_Mt9v117.h"
|
||||
#include "GPIO.h"
|
||||
#include "PWM_Sysfs.h"
|
||||
|
||||
#define OPTICAL_FLOW_ONBOARD_RTPRIO 11
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -58,7 +57,6 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
|
||||
_get_gyro = get_gyro;
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
_videoin = new VideoIn;
|
||||
_pwm = new PWM_Sysfs_Bebop(BEBOP_CAMV_PWM);
|
||||
_pwm->set_freq(BEBOP_CAMV_PWM_FREQ);
|
||||
@ -85,37 +83,29 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
left = (HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH -
|
||||
HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT) / 2;
|
||||
_format = V4L2_PIX_FMT_NV12;
|
||||
#else
|
||||
AP_HAL::panic("OpticalFlow_Onboard: unsupported board\n");
|
||||
#endif
|
||||
|
||||
if (device_path == NULL ||
|
||||
!_videoin->open_device(device_path, memtype)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't open "
|
||||
"video device\n");
|
||||
return;
|
||||
"video device");
|
||||
}
|
||||
|
||||
if (!_videoin->set_format(&_width, &_height, &_format, &_bytesperline,
|
||||
&_sizeimage)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't set video format\n");
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't set video format");
|
||||
return;
|
||||
}
|
||||
|
||||
if (_format != V4L2_PIX_FMT_NV12 && _format != V4L2_PIX_FMT_GREY) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: planar or monochrome format"
|
||||
"needed\n");
|
||||
AP_HAL::panic("OpticalFlow_Onboard: planar or monochrome format needed");
|
||||
}
|
||||
|
||||
if (!_videoin->set_crop(left, top, crop_width, crop_height)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't set video crop\n");
|
||||
return;
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't set video crop");
|
||||
}
|
||||
|
||||
if (!_videoin->allocate_buffers(nbufs)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't allocate "
|
||||
"video buffers\n");
|
||||
return;
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't allocate video buffers");
|
||||
}
|
||||
|
||||
_videoin->prepare_capture();
|
||||
@ -130,23 +120,21 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
* Initialize thread and mutex */
|
||||
ret = pthread_mutex_init(&_mutex, NULL);
|
||||
if (ret != 0) {
|
||||
perror("OpticalFlow_Onboard: failed to init mutex\n");
|
||||
return;
|
||||
AP_HAL::panic("OpticalFlow_Onboard: failed to init mutex");
|
||||
}
|
||||
|
||||
ret = pthread_attr_init(&attr);
|
||||
if (ret != 0) {
|
||||
perror("OpticalFlow_Onboard: failed to init attr\n");
|
||||
return;
|
||||
AP_HAL::panic("OpticalFlow_Onboard: failed to init attr");
|
||||
}
|
||||
pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
|
||||
pthread_attr_setschedpolicy(&attr, SCHED_FIFO);
|
||||
pthread_attr_setschedparam(&attr, ¶m);
|
||||
ret = pthread_create(&_thread, &attr, _read_thread, this);
|
||||
if (ret != 0) {
|
||||
perror("OpticalFlow_Onboard: failed to create thread\n");
|
||||
return;
|
||||
AP_HAL::panic("OpticalFlow_Onboard: failed to create thread");
|
||||
}
|
||||
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
@ -177,9 +165,9 @@ end:
|
||||
return ret;
|
||||
}
|
||||
|
||||
void* OpticalFlow_Onboard::_read_thread(void *arg)
|
||||
void *OpticalFlow_Onboard::_read_thread(void *arg)
|
||||
{
|
||||
OpticalFlow_Onboard* optflow_onboard = (OpticalFlow_Onboard *) arg;
|
||||
OpticalFlow_Onboard *optflow_onboard = (OpticalFlow_Onboard *) arg;
|
||||
|
||||
optflow_onboard->_run_optflow();
|
||||
return NULL;
|
||||
|
@ -12,15 +12,17 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#ifndef __OPTICALFLOW_ONBOARD_H__
|
||||
#define __OPTICALFLOW_ONBOARD_H__
|
||||
#pragma once
|
||||
|
||||
#include <linux/videodev2.h>
|
||||
|
||||
#include <AP_HAL/OpticalFlow.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "CameraSensor.h"
|
||||
#include "Flow_PX4.h"
|
||||
#include "VideoIn.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <linux/videodev2.h>
|
||||
|
||||
class Linux::OpticalFlow_Onboard : public AP_HAL::OpticalFlow {
|
||||
public:
|
||||
@ -37,19 +39,18 @@ private:
|
||||
Flow_PX4* _flow;
|
||||
pthread_t _thread;
|
||||
pthread_mutex_t _mutex;
|
||||
bool _initialized = false;
|
||||
bool _data_available = false;
|
||||
uint32_t _width = 0;
|
||||
uint32_t _height = 0;
|
||||
uint32_t _format = 0;
|
||||
uint32_t _bytesperline = 0;
|
||||
uint32_t _sizeimage = 0;
|
||||
float _pixel_flow_x_integral = 0;
|
||||
float _pixel_flow_y_integral = 0;
|
||||
float _gyro_x_integral = 0;
|
||||
float _gyro_y_integral = 0;
|
||||
uint32_t _integration_timespan = 0;
|
||||
uint8_t _surface_quality = 0;
|
||||
bool _initialized;
|
||||
bool _data_available;
|
||||
uint32_t _width;
|
||||
uint32_t _height;
|
||||
uint32_t _format;
|
||||
uint32_t _bytesperline;
|
||||
uint32_t _sizeimage;
|
||||
float _pixel_flow_x_integral;
|
||||
float _pixel_flow_y_integral;
|
||||
float _gyro_x_integral;
|
||||
float _gyro_y_integral;
|
||||
uint32_t _integration_timespan;
|
||||
uint8_t _surface_quality;
|
||||
AP_HAL::OpticalFlow::Gyro_Cb _get_gyro;
|
||||
};
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user