PX4模块设计之四十一:I2C/SPI Bus Instance基础知识
Posted lida2003
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了PX4模块设计之四十一:I2C/SPI Bus Instance基础知识相关的知识,希望对你有一定的参考价值。
PX4模块设计之四十一:I2C/SPI Bus Instance基础知识
1. 基础知识
- ListNode类
- List类
- BusCLIArguments类
- BusInstanceIterator类
- I2CSPIInstance类
- I2CSPIDriverBase类
- I2CSPIDriver类
- I2C/SPI总线选项
2. 基础类和定义
2.1 ListNode类
主要功能描述:
- 采用类模板扩展ListNode应用范围
- 通过 setSibling 设置成员变量_list_node_sibling
- 通过 getSibling 获取成员变量_list_node_sibling
注:这个类类似于C语言单向链表的一个节点结构声明。
template<class T>
class ListNode
public:
void setSibling(T sibling) _list_node_sibling = sibling;
const T getSibling() const return _list_node_sibling;
protected:
T _list_node_siblingnullptr;
;
2.2 List类
主要功能描述:
- 基于ListNode类实现了单链表功能
- 支持新增一个ListNode操作: void add(T newNode)
- 支持删除一个ListNode操作: bool remove(T removeNode)/void deleteNode(T node)
- 支持列表是否为空判断: bool empty()
- 支持列表清空操作: void clear()
- 支持列表元素数量获取: size_t size()
- 支持列表头元素获取: const T getHead()
- 支持Iterator操作: Iterator begin()/Iterator end()
template<class T>
class List
public:
void add(T newNode)
if (_head == nullptr)
// list is empty, add as head
_head = newNode;
return;
else
// find last node and add to end
T node = _head;
while (node != nullptr)
if (node->getSibling() == nullptr)
// found last node, now add newNode
node->setSibling(newNode);
return;
node = node->getSibling();
bool remove(T removeNode)
if (removeNode == nullptr)
return false;
// base case
if (removeNode == _head)
if (_head != nullptr)
_head = _head->getSibling();
removeNode->setSibling(nullptr);
return true;
for (T node = getHead(); node != nullptr; node = node->getSibling())
// is sibling the node to remove?
if (node->getSibling() == removeNode)
// replace sibling
if (node->getSibling() != nullptr)
node->setSibling(node->getSibling()->getSibling());
else
node->setSibling(nullptr);
removeNode->setSibling(nullptr);
return true;
return false;
struct Iterator
T node;
explicit Iterator(T v) : node(v)
operator T() const return node;
operator T &() return node;
const T &operator* () const return node;
Iterator &operator++ ()
if (node)
node = node->getSibling();
return *this;
;
Iterator begin() return Iterator(getHead());
Iterator end() return Iterator(nullptr);
const T getHead() const return _head;
bool empty() const return getHead() == nullptr;
size_t size() const
size_t sz = 0;
for (auto node = getHead(); node != nullptr; node = node->getSibling())
sz++;
return sz;
void deleteNode(T node)
if (remove(node))
// only delete if node was successfully removed
delete node;
void clear()
auto node = getHead();
while (node != nullptr)
auto next = node->getSibling();
delete node;
node = next;
_head = nullptr;
protected:
T _headnullptr;
;
2.3 BusCLIArguments类
命令行参数配置总线设备。
主要功能描述:
- 支持总线参数命令行解析: parseDefaultArguments
- 支持总线参数检查: validateConfiguration
- 总线参数类型:I2C(_i2c_support) or SPI(_spi_support)
- 支持总线选项: I2C/SPI 内部/外部(bus_option)
- 内部总线号(requested_bus)
- 支持总线工作频率设置(bus_frequency)
- 支持静默启动功能(quiet_start) //do not print a message when startup fails
- 【代码中未见相关功能】支持总线PNP动态功能???(keep_running) //eep driver running even if no device is detected on startup
- 支持是否需要keep_running功能(support_keep_running) //true if keep_running (see above) is supported
- 支持硬件mount方向修正(rotation) //sensor rotation (MAV_SENSOR_ROTATION_* or distance_sensor_s::ROTATION_*)
- 支持设备相关自定义参数(custom1/custom2/custom_data) //driver-specific custom argument
- I2C 总线
I2C Slave地址(i2c_address)
I2C默认频率(default_i2c_frequency) - SPI 总线
SPI芯片选择(chipselect)
SPI工作模式(spi_mode)
SPI默认频率(default_spi_frequency)
class BusCLIArguments
public:
BusCLIArguments(bool i2c_support, bool spi_support)
#if defined(CONFIG_I2C) || defined(CONFIG_SPI)
:
#endif // CONFIG_I2C || CONFIG_SPI
#if defined(CONFIG_I2C)
_i2c_support(i2c_support)
#endif // CONFIG_I2C
#if defined(CONFIG_I2C) && defined(CONFIG_SPI)
,
#endif // CONFIG_I2C && CONFIG_SPI
#if defined(CONFIG_SPI)
_spi_support(spi_support)
#endif // CONFIG_SPI
/**
* Parse CLI arguments (for drivers that don't need any custom arguments, otherwise getopt() should be used)
* @return command (e.g. "start") or nullptr on error or unknown argument
*/
const char *parseDefaultArguments(int argc, char *argv[]);
/**
* Like px4_getopt(), but adds and handles i2c/spi driver-specific arguments
*/
int getOpt(int argc, char *argv[], const char *options);
/**
* returns the current optional argument (for options like 'T:'), or the command (e.g. "start")
* @return nullptr or argument/command
*/
const char *optArg() const return _optarg;
I2CSPIBusOption bus_optionI2CSPIBusOption::All;
int requested_bus-1;
int bus_frequency0;
#if defined(CONFIG_SPI)
int chipselect -1;
spi_mode_e spi_modeSPIDEV_MODE3;
#endif // CONFIG_SPI
#if defined(CONFIG_I2C)
uint8_t i2c_address 0; ///< I2C address (a driver must set the default address)
#endif // CONFIG_I2C
bool quiet_start false; ///< do not print a message when startup fails
bool keep_runningfalse; ///< keep driver running even if no device is detected on startup
Rotation rotationROTATION_NONE; ///< sensor rotation (MAV_SENSOR_ROTATION_* or distance_sensor_s::ROTATION_*)
int custom10; ///< driver-specific custom argument
int custom20; ///< driver-specific custom argument
void *custom_datanullptr; ///< driver-specific custom argument
// driver defaults, if not specified via CLI
#if defined(CONFIG_SPI)
int default_spi_frequency -1; ///< default spi bus frequency (driver needs to set this) [Hz]
#endif // CONFIG_SPI
#if defined(CONFIG_I2C)
int default_i2c_frequency -1; ///< default i2c bus frequency (driver needs to set this) [Hz]
#endif // CONFIG_I2C
bool support_keep_runningfalse; ///< true if keep_running (see above) is supported
private:
bool validateConfiguration();
char _options[32] ;
int _optind1;
const char *_optargnullptr;
#if defined(CONFIG_I2C)
const bool _i2c_support;
#endif // CONFIG_I2C
#if defined(CONFIG_SPI)
const bool _spi_support;
#endif // CONFIG_SPI
;
2.4 BusInstanceIterator类
使用给定的过滤器选项迭代运行实例和/或配置的I2C/SPI总线。
主要功能描述:
- 支持I2C/SPI总线配置
- 支持I2C/SPI总线设备添加
- 支持I2C/SPI总线设备移除
- 支持I2C/SPI总线设备相关属性的获取
class BusInstanceIterator
public:
BusInstanceIterator(const char *module_name, const BusCLIArguments &cli_arguments, uint16_t devid_driver_index);
~BusInstanceIterator();
I2CSPIBusOption configuredBusOption() const return _bus_option;
int runningInstancesCount() const;
bool next();
I2CSPIInstance *instance() const;
void removeInstance();
board_bus_types busType() const;
int bus() const;
uint32_t devid() const;
#if defined(CONFIG_SPI)
spi_drdy_gpio_t DRDYGPIO() const;
#endif // CONFIG_SPI
bool external() const;
int externalBusIndex() const;
int busDeviceIndex() const;
void addInstance(I2CSPIInstance *instance);
#if defined(CONFIG_I2C)
static I2CBusIterator::FilterType i2cFilter(I2CSPIBusOption bus_option);
#endif // CONFIG_I2C
#if defined(CONFIG_SPI)
static SPIBusIterator::FilterType spiFilter(I2CSPIBusOption bus_option);
#endif // CONFIG_SPI
const char *moduleName() const return _module_name;
uint16_t devidDriverIndex() const return _devid_driver_index;
private:
const char *_module_name;
const I2CSPIBusOption _bus_option;
const uint16_t _devid_driver_index;
#if defined(CONFIG_I2C)
const uint8_t _i2c_address;
#endif // CONFIG_I2C
#if defined(CONFIG_SPI)
SPIBusIterator _spi_bus_iterator;
#endif // CONFIG_SPI
#if defined(CONFIG_I2C)
I2CBusIterator _i2c_bus_iterator;
#endif // CONFIG_I2C
List<I2CSPIInstance *>::Iterator _current_instance;
;
2.5 I2CSPIInstance类
I2CSPI实例类对象定义。
主要功能描述:
- 支持I2C/SPI总线实例对象类声明
- 支持I2C/SPI总线类对象BusInstanceIterator/I2CSPIDriverBase友元类
class I2CSPIInstance : public ListNode<I2CSPIInstance *>
public:
virtual ~I2CSPIInstance() = default;
#if defined(CONFIG_I2C)
virtual int8_t get_i2c_address() return _i2c_address;
#endif // CONFIG_I2C
private:
I2CSPIInstance(const I2CSPIDriverConfig &config)
: _module_name(config.module_name), _bus_option(config.bus_option), _bus(config.bus),
_devid_driver_index(config.devid_driver_index), _bus_device_index(config.bus_device_index)
#if defined(CONFIG_I2C)
, _i2c_address(config.i2c_address)
#endif // CONFIG_I2C
friend class BusInstanceIterator;
friend class I2CSPIDriverBase;
const char *_module_name;
const I2CSPIBusOption _bus_option;
const int _bus;
const uint16_t _devid_driver_index;
const int8_t _bus_device_index;
#if defined(CONFIG_I2C)
const int8_t _i2c_address; ///< I2C address (optional)
#endif // CONFIG_I2C
;
2.6 I2CSPIDriverBase类
I2CSPI驱动基础功能类对象定义。
主要功能描述:
- 支持I2C/SPI驱动基础功能模块启动
- 支持I2C/SPI驱动基础功能模块停止
- 支持I2C/SPI驱动基础功能模块状态查询
class I2CSPIDriverBase : public px4::ScheduledWorkItem, public I2CSPIInstance
public:
I2CSPIDriverBase(const I2CSPIDriverConfig &config)
: ScheduledWorkItem(config.module_name, config.wq_config),
I2CSPIInstance(config)
static int module_stop(BusInstanceIterator &iterator);
static int module_status(BusInstanceIterator &iterator);
static int module_custom_method(const BusCLIArguments &cli, BusInstanceIterator &iterator,
bool run_on_work_queue = true);
using instantiate_method = I2CSPIDriverBase * (*)(const I2CSPIDriverConfig &config, int runtime_instance);
protected:
virtual ~I2CSPIDriverBase() = default;
virtual void print_status();
virtual void custom_method(const BusCLIArguments &cli)
/**
* Exiting the module. A driver can override this, for example to unregister interrupt callbacks.
* This will be called from the work queue.
* A module overriding this, needs to call I2CSPIDriverBase::exit_and_cleanup() as the very last statement.
*/
virtual void exit_and_cleanup() ScheduleClear(); _task_exited.store(true);
bool should_exit() const return _task_should_exit.load();
static int module_start(const BusCLIArguments &cli, BusInstanceIterator &iterator, void(*print_usage)(),
instantiate_method instantiate);
private:
static void custom_method_trampoline(void *argument);
void request_stop_and_wait();
px4::atomic_bool _task_should_exitfalse;
px4::atomic_bool _task_exitedfalse;
;
2.7 I2CSPIDriver类
I2CSPI驱动类对象定义。
主要功能描述:
- 支持驱动定制启动
- 支持驱动定义业务运行逻辑
template<class T>
class I2CSPIDriver : public I2CSPIDriverBase
public:
static int module_start(const BusCLIArguments &cli, BusInstanceIterator &iterator)
return I2CSPIDriverBase::module_start(cli, iterator, &T::print_usage, InstantiateHelper<T>::m);
protected:
I2CSPIDriver(const I2CSPIDriverConfig &config)
: I2CSPIDriverBase(config)
virtual ~I2CSPIDriver() = default;
// *INDENT-OFF* remove once there's astyle >3.1 in CI
void Run() final
static_cast<T *>(this)->RunImpl();
if (should_exit())
exit_and_cleanup();
// *INDENT-ON*
private:
// SFINAE to use R::instantiate if it exists, and R::instantiate_default otherwise
template <typename R>
class InstantiateHelper
template <typename C>
static constexpr I2CSPIDriverBase::instantiate_method get(decltype(&C::instantiate)) return &C::instantiate;
template <typename C>
static constexpr I2CSPIDriverBase::instantiate_method get(...) return &C::instantiate_default;
public:
static constexpr I2CSPIDriverBase::instantiate_method m = get<R>(0);
;
static I2CSPIDriverBase *instantiate_default(const I2CSPIDriverConfig &config, int runtime_instance)
T *instance = new T(config);
if (!instance)
PX4_ERR("alloc failed");
return nullptr;
if (OK != instance->init())
delete instance;
return nullptr;
return instance;
;
2.8 I2C/SPI总线选项
PX4系统的I2C/SPI总线分为I2C内部和外部,以及SPI内部和外部四大类。
enum class I2CSPIBusOption : uint8_t
All = 0, ///< select all runnning instances
#if defined(CONFIG_I2C)
I2CInternal,
I2CExternal,
#endif // CONFIG_I2C
#if defined(CONFIG_SPI)
SPIInternal,
SPIExternal,
#endif // CONFIG_SPI
;
3. 总结
注:暂时先整理这些内容,后续随着代码阅读的增加,再补充完善。
4. 参考资料
【1】PX4开源软件框架简明简介
【2】PX4模块设计之十二:High Resolution Timer设计
【3】PX4模块设计之十三:WorkQueue设计
以上是关于PX4模块设计之四十一:I2C/SPI Bus Instance基础知识的主要内容,如果未能解决你的问题,请参考以下文章