mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_HAL_Linux: move mt9v117 patches inside class
Let it be a static const member instead of defining it in a header. The problem with the header is that it will generate conflicting symbols when more than 1 compilation unit includes it.
This commit is contained in:
parent
a32738fd5f
commit
ba5dd88a0b
@ -18,7 +18,6 @@
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
|
||||
#include "CameraSensor_Mt9v117.h"
|
||||
#include "CameraSensor_Mt9v117_Patches.h"
|
||||
|
||||
/* Cam sensor register definitions */
|
||||
#define CHIP_ID 0x0
|
||||
@ -318,7 +317,7 @@ void CameraSensor_Mt9v117::_apply_patch()
|
||||
/* write patch */
|
||||
for (unsigned int i = 0; i < MT9V117_PATCH_LINE_NUM; i++) {
|
||||
_i2c->do_transfer(_addr,
|
||||
patch_lines[i].data, patch_lines[i].size, NULL, 0);
|
||||
_patch_lines[i].data, _patch_lines[i].size, NULL, 0);
|
||||
}
|
||||
|
||||
_write_reg16(LOGICAL_ADDRESS_ACCESS, 0x0000);
|
||||
|
@ -17,17 +17,28 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "CameraSensor.h"
|
||||
|
||||
namespace Linux {
|
||||
|
||||
enum mt9v117_res {
|
||||
MT9V117_QVGA,
|
||||
};
|
||||
|
||||
class Linux::CameraSensor_Mt9v117 : public Linux::CameraSensor {
|
||||
struct mt9v117_patch {
|
||||
uint8_t *data;
|
||||
uint8_t size;
|
||||
};
|
||||
|
||||
#define MT9V117_PATCH_LINE_NUM 13
|
||||
|
||||
class CameraSensor_Mt9v117 : public CameraSensor {
|
||||
public:
|
||||
CameraSensor_Mt9v117(const char *device_path, AP_HAL::I2CDriver *i2c,
|
||||
uint8_t addr, enum mt9v117_res res,
|
||||
uint16_t nrst_gpio, uint32_t clock_freq);
|
||||
|
||||
private:
|
||||
static const struct mt9v117_patch _patch_lines[MT9V117_PATCH_LINE_NUM];
|
||||
|
||||
uint8_t _read_reg8(uint16_t reg);
|
||||
void _write_reg8(uint16_t reg, uint8_t val);
|
||||
uint16_t _read_reg16(uint16_t reg);
|
||||
@ -52,3 +63,5 @@ private:
|
||||
uint16_t _nrst_gpio = 0xFFFF;
|
||||
uint8_t _addr;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -12,7 +12,6 @@
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/* It seems to be mandatory to write these patches by unit of 48 bytes, the
|
||||
* 2 first ones seem to be an address since it increments of 48 at each line
|
||||
@ -20,10 +19,15 @@
|
||||
* writeRegisters(addr, 0xf000, 48, line1);
|
||||
* ...
|
||||
*/
|
||||
#define MT9V117_PATCH_LINE_NUM 13
|
||||
#include "CameraSensor_Mt9v117.h"
|
||||
|
||||
uint8_t patch_line1[] =
|
||||
{
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
static uint8_t patch_line1[] = {
|
||||
0xf0, 0x00, 0x72, 0xcf, 0xff, 0x00, 0x3e, 0xd0, 0x92, 0x00,
|
||||
0x71, 0xcf, 0xff, 0xff, 0xf2, 0x18, 0xb1, 0x10, 0x92, 0x05,
|
||||
0xb1, 0x11, 0x92, 0x04, 0xb1, 0x12, 0x70, 0xcf, 0xff, 0x00,
|
||||
@ -31,8 +35,7 @@ uint8_t patch_line1[] =
|
||||
0xff, 0xff, 0xe7, 0x1c, 0x88, 0x36, 0x09, 0x0f, 0x00, 0xb3
|
||||
};
|
||||
|
||||
uint8_t patch_line2[] =
|
||||
{
|
||||
static uint8_t patch_line2[] = {
|
||||
0xf0, 0x30, 0x69, 0x13, 0xe1, 0x80, 0xd8, 0x08, 0x20, 0xca,
|
||||
0x03, 0x22, 0x71, 0xcf, 0xff, 0xff, 0xe5, 0x68, 0x91, 0x35,
|
||||
0x22, 0x0a, 0x1f, 0x80, 0xff, 0xff, 0xf2, 0x18, 0x29, 0x05,
|
||||
@ -40,8 +43,7 @@ uint8_t patch_line2[] =
|
||||
0x00, 0x00, 0xff, 0xf0, 0x21, 0x8c, 0xf0, 0x10, 0x1a, 0x22
|
||||
};
|
||||
|
||||
uint8_t patch_line3[] =
|
||||
{
|
||||
static uint8_t patch_line3[] = {
|
||||
0xf0, 0x60, 0x10, 0x44, 0x12, 0x20, 0x11, 0x02, 0xf7, 0x87,
|
||||
0x22, 0x4f, 0x03, 0x83, 0x1a, 0x20, 0x10, 0xc4, 0xf0, 0x09,
|
||||
0xba, 0xae, 0x7b, 0x50, 0x1a, 0x20, 0x10, 0x84, 0x21, 0x45,
|
||||
@ -49,8 +51,7 @@ uint8_t patch_line3[] =
|
||||
0x3e, 0xd0, 0xb0, 0x60, 0xb0, 0x25, 0x7e, 0xe0, 0x78, 0xe0
|
||||
};
|
||||
|
||||
uint8_t patch_line4[] =
|
||||
{
|
||||
static uint8_t patch_line4[] = {
|
||||
0xf0, 0x90, 0x71, 0xcf, 0xff, 0xff, 0xf2, 0x18, 0x91, 0x12,
|
||||
0x72, 0xcf, 0xff, 0xff, 0xe7, 0x1c, 0x8a, 0x57, 0x20, 0x04,
|
||||
0x0f, 0x80, 0x00, 0x00, 0xff, 0xf0, 0xe2, 0x80, 0x20, 0xc5,
|
||||
@ -58,8 +59,7 @@ uint8_t patch_line4[] =
|
||||
0xff, 0x00, 0x3e, 0xd0, 0xb1, 0x04, 0x7e, 0xe0, 0x78, 0xe0
|
||||
};
|
||||
|
||||
uint8_t patch_line5[] =
|
||||
{
|
||||
static uint8_t patch_line5[] = {
|
||||
0xf0, 0xc0, 0x70, 0xcf, 0xff, 0xff, 0xe7, 0x1c, 0x88, 0x57,
|
||||
0x71, 0xcf, 0xff, 0xff, 0xf2, 0x18, 0x91, 0x13, 0xea, 0x84,
|
||||
0xb8, 0xa9, 0x78, 0x10, 0xf0, 0x03, 0xb8, 0x89, 0xb8, 0x8c,
|
||||
@ -67,8 +67,7 @@ uint8_t patch_line5[] =
|
||||
0x7e, 0xe0, 0xc0, 0xf1, 0x09, 0x1e, 0x03, 0xc0, 0xc1, 0xa1
|
||||
};
|
||||
|
||||
uint8_t patch_line6[] =
|
||||
{
|
||||
static uint8_t patch_line6[] = {
|
||||
0xf0, 0xf0, 0x75, 0x08, 0x76, 0x28, 0x77, 0x48, 0xc2, 0x40,
|
||||
0xd8, 0x20, 0x71, 0xcf, 0x00, 0x03, 0x20, 0x67, 0xda, 0x02,
|
||||
0x08, 0xae, 0x03, 0xa0, 0x73, 0xc9, 0x0e, 0x25, 0x13, 0xc0,
|
||||
@ -76,8 +75,7 @@ uint8_t patch_line6[] =
|
||||
0x01, 0x00, 0xd8, 0x00, 0xb8, 0x9e, 0x0e, 0x5a, 0x03, 0x20
|
||||
};
|
||||
|
||||
uint8_t patch_line7[] =
|
||||
{
|
||||
static uint8_t patch_line7[] = {
|
||||
0xf1, 0x20, 0xd9, 0x01, 0xd8, 0x00, 0xb8, 0x9e, 0x0e, 0xb6,
|
||||
0x03, 0x20, 0xd9, 0x01, 0x8d, 0x14, 0x08, 0x17, 0x01, 0x91,
|
||||
0x8d, 0x16, 0xe8, 0x07, 0x0b, 0x36, 0x01, 0x60, 0xd8, 0x07,
|
||||
@ -85,8 +83,7 @@ uint8_t patch_line7[] =
|
||||
0xd8, 0x00, 0x20, 0xca, 0x02, 0x62, 0x00, 0xc9, 0x03, 0xe0
|
||||
};
|
||||
|
||||
uint8_t patch_line8[] =
|
||||
{
|
||||
static uint8_t patch_line8[] = {
|
||||
0xf1, 0x50, 0xc0, 0xa1, 0x78, 0xe0, 0xc0, 0xf1, 0x08, 0xb2,
|
||||
0x03, 0xc0, 0x76, 0xcf, 0xff, 0xff, 0xe5, 0x40, 0x75, 0xcf,
|
||||
0xff, 0xff, 0xe5, 0x68, 0x95, 0x17, 0x96, 0x40, 0x77, 0xcf,
|
||||
@ -94,8 +91,7 @@ uint8_t patch_line8[] =
|
||||
0x97, 0x40, 0x0a, 0x11, 0x00, 0x40, 0x0b, 0x0a, 0x01, 0x00
|
||||
};
|
||||
|
||||
uint8_t patch_line9[] =
|
||||
{
|
||||
static uint8_t patch_line9[] = {
|
||||
0xf1, 0x80, 0x95, 0x17, 0xb6, 0x00, 0x95, 0x18, 0xb7, 0x00,
|
||||
0x76, 0xcf, 0xff, 0xff, 0xe5, 0x44, 0x96, 0x20, 0x95, 0x15,
|
||||
0x08, 0x13, 0x00, 0x40, 0x0e, 0x1e, 0x01, 0x20, 0xd9, 0x00,
|
||||
@ -103,8 +99,7 @@ uint8_t patch_line9[] =
|
||||
0xe7, 0x1c, 0x77, 0xcf, 0xff, 0xff, 0xe5, 0x46, 0x97, 0x40
|
||||
};
|
||||
|
||||
uint8_t patch_line10[] =
|
||||
{
|
||||
static uint8_t patch_line10[] = {
|
||||
0xf1, 0xb0, 0x8d, 0x16, 0x76, 0xcf, 0xff, 0xff, 0xe5, 0x48,
|
||||
0x8d, 0x37, 0x08, 0x0d, 0x00, 0x81, 0x96, 0x40, 0x09, 0x15,
|
||||
0x00, 0x80, 0x0f, 0xd6, 0x01, 0x00, 0x8d, 0x16, 0xb7, 0x00,
|
||||
@ -112,8 +107,7 @@ uint8_t patch_line10[] =
|
||||
0x03, 0xc0, 0xc0, 0xf1, 0x0d, 0x9e, 0x01, 0x00, 0xe8, 0x04
|
||||
};
|
||||
|
||||
uint8_t patch_line11[] =
|
||||
{
|
||||
static uint8_t patch_line11[] = {
|
||||
0xf1, 0xe0, 0xff, 0x88, 0xf0, 0x0a, 0x0d, 0x6a, 0x01, 0x00,
|
||||
0x0d, 0x8e, 0x01, 0x00, 0xe8, 0x7e, 0xff, 0x85, 0x0d, 0x72,
|
||||
0x01, 0x00, 0xff, 0x8c, 0xff, 0xa7, 0xff, 0xb2, 0xd8, 0x00,
|
||||
@ -121,8 +115,7 @@ uint8_t patch_line11[] =
|
||||
0x81, 0x41, 0xe0, 0x02, 0x81, 0x20, 0x08, 0xf7, 0x81, 0x34
|
||||
};
|
||||
|
||||
uint8_t patch_line12[] =
|
||||
{
|
||||
static uint8_t patch_line12[] = {
|
||||
0xf2, 0x10, 0xa1, 0x40, 0xd8, 0x00, 0xc0, 0xd1, 0x7e, 0xe0,
|
||||
0x53, 0x51, 0x30, 0x34, 0x20, 0x6f, 0x6e, 0x5f, 0x73, 0x74,
|
||||
0x61, 0x72, 0x74, 0x5f, 0x73, 0x74, 0x72, 0x65, 0x61, 0x6d,
|
||||
@ -130,18 +123,12 @@ uint8_t patch_line12[] =
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
uint8_t patch_line13[] =
|
||||
{
|
||||
static uint8_t patch_line13[] = {
|
||||
0xf2, 0x40, 0xff, 0xff, 0xe8, 0x28, 0xff, 0xff, 0xf0, 0xe8,
|
||||
0xff, 0xff, 0xe8, 0x08, 0xff, 0xff, 0xf1, 0x54
|
||||
};
|
||||
|
||||
struct mt9v117_patch_line {
|
||||
uint8_t *data;
|
||||
uint8_t size;
|
||||
};
|
||||
|
||||
struct mt9v117_patch_line patch_lines[MT9V117_PATCH_LINE_NUM] = {
|
||||
const struct mt9v117_patch CameraSensor_Mt9v117::_patch_lines[MT9V117_PATCH_LINE_NUM] = {
|
||||
{patch_line1, sizeof(patch_line1)},
|
||||
{patch_line2, sizeof(patch_line2)},
|
||||
{patch_line3, sizeof(patch_line3)},
|
||||
@ -156,3 +143,5 @@ struct mt9v117_patch_line patch_lines[MT9V117_PATCH_LINE_NUM] = {
|
||||
{patch_line12, sizeof(patch_line12)},
|
||||
{patch_line13, sizeof(patch_line13)}
|
||||
};
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user