mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_HAL_Linux: OpticalFlow swap crop and scale order
In order to be easier to understand the image manipulation for the ones who read this part, since the order makes no difference in this stage.
This commit is contained in:
parent
cbb313ec2c
commit
7033e4d8ed
@ -90,6 +90,10 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
"video device");
|
||||
}
|
||||
|
||||
if (!_videoin->set_crop(left, top, crop_width, crop_height)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't set video crop");
|
||||
}
|
||||
|
||||
if (!_videoin->set_format(&_width, &_height, &_format, &_bytesperline,
|
||||
&_sizeimage)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't set video format");
|
||||
@ -100,10 +104,6 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
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");
|
||||
}
|
||||
|
||||
if (!_videoin->allocate_buffers(nbufs)) {
|
||||
AP_HAL::panic("OpticalFlow_Onboard: couldn't allocate video buffers");
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user