mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
refactor pcf8583: use driver base class
This commit is contained in:
parent
bb4ff04caf
commit
fb6ce09dc4
@ -145,6 +145,7 @@
|
||||
#define DRV_LED_DEVTYPE_RGBLED_NCP5623C 0x7b
|
||||
#define DRV_BAT_DEVTYPE_SMBUS 0x7c
|
||||
#define DRV_SENS_DEVTYPE_IRLOCK 0x7d
|
||||
#define DRV_SENS_DEVTYPE_PCF8583 0x7e
|
||||
|
||||
#define DRV_DEVTYPE_UNUSED 0xff
|
||||
|
||||
|
||||
@ -33,18 +33,13 @@
|
||||
|
||||
#include "PCF8583.hpp"
|
||||
|
||||
PCF8583::PCF8583(int bus, int address) :
|
||||
I2C("PCF8583", nullptr, bus, address, 400000),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id())),
|
||||
ModuleParams(nullptr)
|
||||
PCF8583::PCF8583(I2CSPIBusOption bus_option, const int bus, int bus_frequency) :
|
||||
I2C("PCF8583", nullptr, bus, PCF8583_BASEADDR_DEFAULT, bus_frequency),
|
||||
ModuleParams(nullptr),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus)
|
||||
{
|
||||
}
|
||||
|
||||
PCF8583::~PCF8583()
|
||||
{
|
||||
ScheduleClear();
|
||||
}
|
||||
|
||||
int PCF8583::init()
|
||||
{
|
||||
set_device_address(_param_pcf8583_addr.get());
|
||||
@ -53,9 +48,9 @@ int PCF8583::init()
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
PX4_INFO("addr: %d, pool: %d, reset: %d, magenet: %d", get_device_address(), _param_pcf8583_pool.get(),
|
||||
_param_pcf8583_reset.get(),
|
||||
_param_pcf8583_magnet.get());
|
||||
PX4_DEBUG("addr: %d, pool: %d, reset: %d, magenet: %d", get_device_address(), _param_pcf8583_pool.get(),
|
||||
_param_pcf8583_reset.get(),
|
||||
_param_pcf8583_magnet.get());
|
||||
|
||||
// set counter mode
|
||||
setRegister(0x00, 0b00100000);
|
||||
@ -114,7 +109,7 @@ uint8_t PCF8583::readRegister(uint8_t reg)
|
||||
return rcv;
|
||||
}
|
||||
|
||||
void PCF8583::Run()
|
||||
void PCF8583::RunImpl()
|
||||
{
|
||||
// read sensor and compute frequency
|
||||
int oldcount = _count;
|
||||
@ -145,7 +140,8 @@ void PCF8583::Run()
|
||||
_rpm_pub.publish(msg);
|
||||
}
|
||||
|
||||
void PCF8583::print_info()
|
||||
void PCF8583::print_status()
|
||||
{
|
||||
I2CSPIDriverBase::print_status();
|
||||
PX4_INFO("poll interval: %d us", _param_pcf8583_pool.get());
|
||||
}
|
||||
|
||||
@ -45,7 +45,7 @@
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/rpm.h>
|
||||
@ -54,19 +54,24 @@
|
||||
/* Configuration Constants */
|
||||
#define PCF8583_BASEADDR_DEFAULT 0x50
|
||||
|
||||
class PCF8583 : public device::I2C, public px4::ScheduledWorkItem, public ModuleParams
|
||||
class PCF8583 : public device::I2C, public ModuleParams, public I2CSPIDriver<PCF8583>
|
||||
{
|
||||
public:
|
||||
PCF8583(int bus = PX4_I2C_BUS_EXPANSION, int address = PCF8583_BASEADDR_DEFAULT);
|
||||
~PCF8583() override;
|
||||
PCF8583(I2CSPIBusOption bus_option, const int bus, int bus_frequency);
|
||||
~PCF8583() override = default;
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void RunImpl();
|
||||
|
||||
int init() override;
|
||||
void print_info();
|
||||
void print_status() override;
|
||||
|
||||
private:
|
||||
|
||||
int probe() override;
|
||||
void Run() override ; // Perform a poll cycle; overide for ScheduledWorkItem
|
||||
|
||||
int getCounter();
|
||||
void resetCounter();
|
||||
|
||||
@ -34,109 +34,60 @@
|
||||
#include "PCF8583.hpp"
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
|
||||
namespace pcf8583
|
||||
void
|
||||
PCF8583::print_usage()
|
||||
{
|
||||
PCF8583 *g_dev{nullptr};
|
||||
PRINT_MODULE_USAGE_NAME("pcf8583", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
static int start(int i2c_bus)
|
||||
I2CSPIDriverBase *PCF8583::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
if (g_dev != nullptr) {
|
||||
PX4_WARN("already started");
|
||||
return 0;
|
||||
PCF8583 *instance = new PCF8583(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency);
|
||||
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
// create the driver
|
||||
g_dev = new PCF8583(i2c_bus);
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
PX4_ERR("driver alloc failed");
|
||||
return instance;
|
||||
}
|
||||
extern "C" __EXPORT int pcf8583_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = PCF8583;
|
||||
BusCLIArguments cli{true, false};
|
||||
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (g_dev->init() != PX4_OK) {
|
||||
PX4_ERR("driver init failed");
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
return -1;
|
||||
}
|
||||
|
||||
PX4_INFO("pcf8583 for bus: %d started.", i2c_bus);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int stop()
|
||||
{
|
||||
if (g_dev == nullptr) {
|
||||
PX4_WARN("driver not running");
|
||||
return -1;
|
||||
}
|
||||
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int status()
|
||||
{
|
||||
if (g_dev == nullptr) {
|
||||
PX4_INFO("driver not running");
|
||||
return 0;
|
||||
}
|
||||
|
||||
g_dev->print_info();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int usage()
|
||||
{
|
||||
PX4_INFO("missing command: try 'start', 'stop', 'status'");
|
||||
PX4_INFO("options:");
|
||||
PX4_INFO(" -b i2cbus (%d)", PX4_I2C_BUS_EXPANSION);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
} // namespace pcf8583
|
||||
|
||||
extern "C" int pcf8583_main(int argc, char *argv[])
|
||||
{
|
||||
int i2c_bus = PX4_I2C_BUS_EXPANSION;
|
||||
int myoptind = 1;
|
||||
int ch = 0;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
// start options
|
||||
while ((ch = px4_getopt(argc, argv, "b:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'b':
|
||||
i2c_bus = atoi(myoptarg);
|
||||
break;
|
||||
|
||||
default:
|
||||
return pcf8583::usage();
|
||||
}
|
||||
}
|
||||
|
||||
if (myoptind >= argc) {
|
||||
pcf8583::usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
const char *verb = argv[myoptind];
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_SENS_DEVTYPE_PCF8583);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return pcf8583::start(i2c_bus);
|
||||
|
||||
} else if (!strcmp(verb, "stop")) {
|
||||
return pcf8583::stop();
|
||||
|
||||
} else if (!strcmp(verb, "status")) {
|
||||
return pcf8583::status();
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
return pcf8583::usage();
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user