Skip to content

Commit

Permalink
Analog Devices ADIS16497 move to PX4Accelerometer/PX4Gyroscope and cl…
Browse files Browse the repository at this point in the history
…eanup
  • Loading branch information
dagar committed Jul 2, 2019
1 parent cdadb39 commit 10bff75
Show file tree
Hide file tree
Showing 10 changed files with 137 additions and 637 deletions.
374 changes: 89 additions & 285 deletions src/drivers/imu/adis16497/ADIS16497.cpp

Large diffs are not rendered by default.

89 changes: 14 additions & 75 deletions src/drivers/imu/adis16497/ADIS16497.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
* Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
Expand Down Expand Up @@ -36,29 +36,18 @@
*
*/

#ifndef DRIVERS_IMU_ADIS16497_ADIS16497_HPP_
#define DRIVERS_IMU_ADIS16497_ADIS16497_HPP_
#pragma once

#include <drivers/device/ringbuffer.h>
#include <drivers/device/spi.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <mathlib/math/filter/LowPassFilter2pVector3f.hpp>
#include <drivers/device/integrator.h>
#include <lib/conversion/rotation.h>
#include <perf/perf_counter.h>
#include <ecl/geo/geo.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>

#define ADIS16497_GYRO_DEFAULT_RATE 1000
#define ADIS16497_GYRO_DEFAULT_DRIVER_FILTER_FREQ 80

#define ADIS16497_ACCEL_DEFAULT_RATE 1000
#define ADIS16497_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>

// TODO : This is a copy of the NuttX CRC32 table
static const uint32_t crc32_tab[] = {
static constexpr uint32_t crc32_tab[] = {
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
Expand Down Expand Up @@ -93,68 +82,30 @@ static const uint32_t crc32_tab[] = {
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
};

class ADIS16497_gyro;

class ADIS16497 : public device::SPI, public px4::ScheduledWorkItem
{
public:
ADIS16497(int bus, const char *path_accel, const char *path_gyro, uint32_t device, enum Rotation rotation);
ADIS16497(int bus, uint32_t device, enum Rotation rotation = ROTATION_NONE);
virtual ~ADIS16497();

virtual int init();

virtual int ioctl(struct file *filp, int cmd, unsigned long arg);

void print_info();

protected:
virtual int probe();

friend class ADIS16497_gyro;

virtual int gyro_ioctl(struct file *filp, int cmd, unsigned long arg);

private:
ADIS16497_gyro *_gyro{nullptr};

unsigned _call_interval{1000};

struct gyro_calibration_s _gyro_scale {};

// gyro 0.025 °/sec/LSB
float _gyro_range_scale{0.025f};
float _gyro_range_rad_s{math::radians(500.0f)};

struct accel_calibration_s _accel_scale {};

// accel 1.25 mg/LSB
float _accel_range_scale{1.25f * CONSTANTS_ONE_G / 1000.0f};
float _accel_range_m_s2{40.0f * CONSTANTS_ONE_G};

orb_advert_t _accel_topic{nullptr};

int _accel_orb_class_instance{-1};
int _accel_class_instance{-1};

unsigned _sample_rate{1000};
PX4Accelerometer _px4_accel;
PX4Gyroscope _px4_gyro;

perf_counter_t _sample_perf;
perf_counter_t _sample_interval_perf;

perf_counter_t _sample_perf;
perf_counter_t _bad_transfers;

math::LowPassFilter2pVector3f _gyro_filter{ADIS16497_GYRO_DEFAULT_RATE, ADIS16497_GYRO_DEFAULT_DRIVER_FILTER_FREQ};
math::LowPassFilter2pVector3f _accel_filter{ADIS16497_ACCEL_DEFAULT_RATE, ADIS16497_ACCEL_DEFAULT_DRIVER_FILTER_FREQ};

Integrator _accel_int{4000, false};
Integrator _gyro_int{4000, true};

enum Rotation _rotation;

#pragma pack(push, 1)
/**
* Report conversation with the ADIS16497, including command byte.
*/
// Report conversation with the ADIS16497, including command byte.
struct ADISReport {
uint16_t cmd;
uint16_t ZEROES;
Expand Down Expand Up @@ -182,12 +133,12 @@ class ADIS16497 : public device::SPI, public px4::ScheduledWorkItem
/**
* Start automatic measurement.
*/
void start();
void start();

/**
* Stop automatic measurement.
*/
void stop();
void stop();

/**
* Reset chip.
Expand All @@ -196,10 +147,6 @@ class ADIS16497 : public device::SPI, public px4::ScheduledWorkItem
*/
int reset();

/**
* Called by the ScheduledWorkItem at the specified rate if
* automatic polling is enabled.
*/
void Run() override;

static int data_ready_interrupt(int irq, void *context, void *arg);
Expand All @@ -209,21 +156,15 @@ class ADIS16497 : public device::SPI, public px4::ScheduledWorkItem
*/
int measure();

void publish_accel(const hrt_abstime &t, const ADISReport &report);
void publish_gyro(const hrt_abstime &t, const ADISReport &report);

uint16_t read_reg16(uint8_t reg);

void write_reg(uint8_t reg, uint8_t value);
void write_reg16(uint8_t reg, uint16_t value);

// ADIS16497 onboard self test
bool self_test_sensor();

ADIS16497(const ADIS16497 &);
ADIS16497 operator=(const ADIS16497 &);
bool self_test();

uint32_t crc32(const uint16_t *data, size_t len)
uint32_t crc32(const uint16_t *data, size_t len) const
{
uint32_t crc = 0xffffffff;
uint8_t tbl_idx;
Expand All @@ -245,5 +186,3 @@ class ADIS16497 : public device::SPI, public px4::ScheduledWorkItem
}

};

#endif /* DRIVERS_IMU_ADIS16497_ADIS16497_HPP_ */
79 changes: 0 additions & 79 deletions src/drivers/imu/adis16497/ADIS16497_gyro.cpp

This file was deleted.

71 changes: 0 additions & 71 deletions src/drivers/imu/adis16497/ADIS16497_gyro.hpp

This file was deleted.

9 changes: 6 additions & 3 deletions src/drivers/imu/adis16497/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,12 @@ px4_add_module(
MAIN adis16497
STACK_MAIN 1200
COMPILE_FLAGS
-Wno-cast-align # TODO: fix and enable
-Wno-cast-align # TODO: fix and enable
SRCS
ADIS16497.cpp
ADIS16497_gyro.cpp
ADIS16497_main.cpp
ADIS16497.hpp
adis16497_main.cpp
DEPENDS
drivers_accelerometer
drivers_gyroscope
)
Loading

0 comments on commit 10bff75

Please sign in to comment.