PX4模块设计之四十三:icm20689模块

1. icm20689模块简介

icm20689 <command> [arguments...]
 Commands:
   start
     [-s]        Internal SPI bus(es)
     [-S]        External SPI bus(es)
     [-b <val>]  board-specific bus (default=all) (external SPI: n-th bus
                 (default=1))
     [-c <val>]  chip-select pin (for internal SPI) or index (for external SPI)
     [-m <val>]  SPI mode
     [-f <val>]  bus frequency in kHz
     [-q]        quiet startup (no message if no device found)
     [-R <val>]  Rotation
                 default: 0

   stop

   status        print status info

注1:print_usage函数是具体对应实现。

class ICM20689 : public device::SPI, public I2CSPIDriver<ICM20689>
class I2CSPIDriver : public I2CSPIDriverBase
class I2CSPIDriverBase : public px4::ScheduledWorkItem, public I2CSPIInstance
class ScheduledWorkItem : public WorkItem
class WorkItem : public IntrusiveSortedListNode<WorkItem *>, public IntrusiveQueueNode<WorkItem *>
class I2CSPIInstance : public ListNode<I2CSPIInstance *>


ICM20689  //类继承关系
 ├──> I2CSPIDriver
 │   └──> I2CSPIDriverBase
 │       ├──> px4::ScheduledWorkItem
 │       │   └──> WorkItem
 │       │       ├──> IntrusiveSortedListNode
 │       │       └──> IntrusiveQueueNode
 │       └──> I2CSPIInstance
 │           └──> ListNode
 └──> device::SPI

注2:ICM20689模块就是针对ICM20689硬件芯片进行管理和数据采集的模块。

2. 模块入口函数

2.1 主入口icm20689_main

模块支持start/stop/status命令,除此以外支持BusCLIArguments的I2C/SPI默认参数选项"RXIa:Ssc: m:kb:f:q"。

icm20689_main
 ├──> using ThisDriver = ICM20689
 ├──> BusCLIArguments cli{false, true}
 ├──> cli.default_spi_frequency = SPI_SPEED
 ├──> <while ((ch = cli.getOpt(argc, argv, "R:")) != EOF)>
 │   └──> <case 'R'>
 │       ├──> cli.rotation = (enum Rotation)atoi(cli.optArg())
 │       └──> break
 ├──> const char *verb = cli.optArg()
 ├──> <!verb>
 │   ├──> ThisDriver::print_usage()
 │   └──> return -1
 ├──> BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_ICM20689)
 ├──> <!strcmp(verb, "start")>
 │   └──> return ThisDriver::module_start(cli, iterator)   //模块启动
 ├──> <(!strcmp(verb, "stop")>
 │   └──> return ThisDriver::module_stop(iterator)  //模块停止
 ├──> <!strcmp(verb, "status")>
 │   └──> return ThisDriver::module_status(iterator)  //模块状态
 ├──> ThisDriver::print_usage()
 └──> return -1

2.2 自定义子命令custom_command

注:该模块采用了纯C语言代码实现,在main函数中直接执行命令,无需ModuleBase的custom_command重载实现。

2.3 模块状态print_status【重载】

该模块采用了纯C语言代码实现,在main函数中直接执行ThisDriver::print_usage()函数,无需ModuleBase的模块状态print_status重载实现。

ICM20689::print_usage

void ICM20689::print_usage()
{
	PRINT_MODULE_USAGE_NAME("icm20689", "driver");
	PRINT_MODULE_USAGE_SUBCATEGORY("imu");
	PRINT_MODULE_USAGE_COMMAND("start");
	PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
	PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
	PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}

3. ICM20689模块重要函数

3.1 模块启动ThisDriver::module_start

启动过程会将以下驱动信息关联到设备实例上:

  1. static I2CSPIDriverBase *I2CSPIDriver::instantiate_default(const I2CSPIDriverConfig &config, int runtime_instance)
  2. int ICM20689::init()
  3. void ICM20689::RunImpl()
  4. void I2CSPIDriver::Run() final
ThisDriver::module_start(ICM20689::module_start)
 └──> I2CSPIDriver::module_start
     └──> I2CSPIDriverBase::module_start

注:I2CSPIDriverBase::module_start会进行第一次的Run激活(px4::WorkItemSingleShot)。

3.2 模块停止ThisDriver::module_stop

ThisDriver::module_stop(ICM20689::module_stop)
 └──> I2CSPIDriverBase::module_stop

注:I2CSPIDriverBase类的通用方法,不在这里展开。

3.3 模块状态ThisDriver::module_status

ThisDriver::module_status(ICM20689::module_status)
 └──> I2CSPIDriverBase::module_status

注:I2CSPIDriverBase类的通用方法,不在这里展开。

3.4 设备实例对象初始化I2CSPIDriver::instantiate_default

该方法在I2CSPIDriverBase::module_start函数里面调用,其目的是新建一个设备对象实例,并进行初始化。

I2CSPIDriver::instantiate_default
 ├──> instance = new T(config)   // 新建一个ICM20689设备对象实例
 ├──> <!instance>
 │   ├──> PX4_ERR("alloc failed")
 │   └──> return nullptr
 ├──> <OK != instance->init()>  // ICM20689设备对象实例初始化
 │   ├──> delete instance
 │   └──> return nullptr
 └──> return instance

3.5 ICM20689设备实例对象初始化ICM20689::init

ICM20689设备实例对象初始化

ICM20689::init
 ├──> int ret = SPI::init()  // SPI总线初始化
 ├──> <ret != PX4_OK>
 │   ├──> DEVICE_DEBUG("SPI::init failed (%i)", ret)
 │   └──> return ret
 └──> return Reset() ? 0 : -1  // 重置模块,然后触发ScheduleNow

3.6 设备实例对象任务I2CSPIDriver::Run()

ICM20689设备初始化时以及设置定时时间,定时轮询Run过程,并调用业务实现方法RunImpl。

I2CSPIDriver::Run
 ├──> static_cast<T *>(this)->RunImpl()
 └──> <should_exit()>
     └──> exit_and_cleanup()  //优雅退出处理

3.7 ICM20689设备实例对象任务ICM20689::RunImpl

根据ICM20689模块业务状态机变化,进行业务操作,发布gyro, accel, temperature消息

ICM20689::RunImpl
 ├──> const hrt_abstime now = hrt_absolute_time()
 └──> switch (_state) {
     ├──> <case STATE::RESET>
     │   ├──> [PWR_MGMT_1: Device Reset	]
     │   └──> ScheduleDelayed(100_ms)
     ├──> <case STATE::WAIT_FOR_RESET>
     │   ├──> <Reset OK??? (RegisterRead(Register::WHO_AM_I) == WHOAMI)  && (RegisterRead(Register::PWR_MGMT_1) == 0x40)>
     │   │   ├──> [offset registers (factory calibration) should not change during normal operation]
     │   │   ├──> [Wakeup and reset digital signal path		
     │   │   ├──> [_state = STATE::CONFIGURE  // if reset succeeded then configure
     │   │   └──> ScheduleDelayed(35_ms) // max 35 ms start-up time from sleep
     │   └──> <else Reset failed>  // RESET not complete
     │       ├──> <hrt_elapsed_time(&_reset_timestamp) > 1000_ms>  // Reset failed, retrying
     │       │   ├──> _state = STATE::RESET
     │       │   └──> ScheduleDelayed(100_ms)
     │       └──> <else>  // Reset not complete, check again in 10 ms
     │           └──> ScheduleDelayed(10_ms)
     ├──> <case STATE::CONFIGURE>
     │   ├──> <Configure()> // if configure succeeded then start reading from FIFO
     │   │   ├──> _state = STATE::FIFO_READ
     │   │   │   ├──> <DataReadyInterruptConfigure()>
     │   │   │   │   ├──> _data_ready_interrupt_enabled = true
     │   │   │   │   └──> ScheduleDelayed(100_ms)  // backup schedule as a watchdog timeout
     │   │   │   └──> <else>
     │   │   │       ├──> _data_ready_interrupt_enabled = false
     │   │   │       └──> ScheduleOnInterval(_fifo_empty_interval_us, _fifo_empty_interval_us)
     │   │   └──> FIFOReset()
     │   └──> <else > // CONFIGURE not complete
     │       ├──> <hrt_elapsed_time(&_reset_timestamp) > 1000_ms>  // Configure failed, resetting
     │       │   └──> _state = STATE::RESET
     │       ├──> <else>   // Configure failed, retrying
     │       └──> ScheduleDelayed(100_ms)
     └──> <case STATE::FIFO_READ>
         ├──> [Execption handling procedures]
         ├──> [Update temperature readings]
         └──> [Update gyro and accel]  //FIFORead function and ProcessGyro/ProcessAccel

4. 总结

具体逻辑业务后续再做深入,从模块代码角度:

  • 输入: 芯片(硬件)

  • 输出: 修改OSD显示内容

uORB::PublicationMulti<sensor_gyro_s> _sensor_pub{ORB_ID(sensor_gyro)};
uORB::PublicationMulti<sensor_gyro_fifo_s>  _sensor_fifo_pub{ORB_ID(sensor_gyro_fifo)};

uORB::PublicationMulti<sensor_accel_s> _sensor_pub{ORB_ID(sensor_accel)};
uORB::PublicationMulti<sensor_accel_fifo_s>  _sensor_fifo_pub{ORB_ID(sensor_accel_fifo)};

注1:参考class PX4Accelerometerclass PX4Gyroscope

注2:参考ICM 20689芯片规格书: DS-000143-ICM-20689-TYP-v1.1.pdf

5. 参考资料

【1】PX4开源软件框架简明简介
【2】PX4模块设计之十一:Built-In框架
【3】PX4模块设计之十二:High Resolution Timer设计
【4】PX4模块设计之十三:WorkQueue设计
【5】PX4模块设计之十七:ModuleBase模块
【6】PX4模块设计之三十:Hysteresis类
【7】PX4 modules_main
【8】PX4模块设计之四十一:I2C/SPI Bus Instance基础知识

  • 1
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值