Refactor PCA9685 (#26379)

* refactor: use parseDefaultArguments

* style: reverted changes to docs (should be auto-generated)

* refactor: use parseDefaultArguments

* style: reverted changes to docs (should be auto-generated)
This commit is contained in:
Phil-Engljaehringer 2026-03-05 15:31:12 +01:00 committed by GitHub
parent 61d2173524
commit 010f6dcbae
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
9 changed files with 44 additions and 87 deletions

View File

@ -100,7 +100,7 @@ bmp388 -I start
# Start an external PWM generator
if param greater PCA9685_EN_BUS 0
then
pca9685_pwm_out start
pca9685_pwm_out start -X
fi
unset HAVE_PM2

View File

@ -20,5 +20,5 @@ bmp388 -I -b 2 start
# Start an external PWM generator
if param greater PCA9685_EN_BUS 0
then
pca9685_pwm_out start
pca9685_pwm_out start -X
fi

View File

@ -38,5 +38,5 @@ afbrs50 start
# Start an external PWM generator
if param greater PCA9685_EN_BUS 0
then
pca9685_pwm_out start
pca9685_pwm_out start -X
fi

View File

@ -77,5 +77,5 @@ ist8310 -X -b 1 -R 10 start
# Start an external PWM generator
if param greater PCA9685_EN_BUS 0
then
pca9685_pwm_out start
pca9685_pwm_out start -X
fi

View File

@ -28,7 +28,7 @@ then
echo "ads1115 not found."
fi
if ! pca9685_pwm_out start
if ! pca9685_pwm_out start -X
then
echo "pca9685_pwm_out not found."
fi

View File

@ -41,7 +41,7 @@ ms5611 start -I
ads1115 start -I
# PWM
pca9685_pwm_out start
pca9685_pwm_out start -X
control_allocator start
# external GPS & compass

View File

@ -41,7 +41,7 @@ ms5611 start -I
ads1115 start -I
# PWM
pca9685_pwm_out start
pca9685_pwm_out start -X
control_allocator start
# external GPS & compass

View File

@ -35,6 +35,7 @@
#include <cstdint>
#include <drivers/device/i2c.h>
#include <px4_boardconfig.h>
#include <px4_platform_common/i2c_spi_buses.h>
#define PCA9685_REG_MODE1 0x00 // Mode register 1
#define PCA9685_REG_MODE2 0x01 // Mode register 2

View File

@ -332,7 +332,7 @@ that can be accepted by most ESCs and servos.
### Examples
It is typically started with:
$ pca9685_pwm_out start -a 0x40 -b 1
$ pca9685_pwm_out start -X -a 0x40 -b 1
)DESCR_STR");
@ -346,13 +346,18 @@ $ pca9685_pwm_out start -a 0x40 -b 1
}
int PCA9685Wrapper::print_status() {
int ret = ModuleBase::print_status();
PX4_INFO("PCA9685 @I2C Bus %d, address 0x%.2x, real frequency %.2f",
pca9685->get_device_bus(),
pca9685->get_device_address(),
(double)(pca9685->getFreq()));
int ret = ModuleBase::print_status();
PX4_INFO("PCA9685 @I2C Bus %d, address 0x%.2x, real frequency %.2f",
pca9685->get_device_bus(),
pca9685->get_device_address(),
(double)(pca9685->getFreq()));
return ret;
perf_print_counter(_cycle_perf);
perf_print_counter(_comms_errors);
perf_print_counter(_registers_invalid_reset);
perf_print_counter(_registers_transfer_reset);
return ret;
}
int PCA9685Wrapper::custom_command(int argc, char **argv) {
@ -360,92 +365,43 @@ int PCA9685Wrapper::custom_command(int argc, char **argv) {
}
int PCA9685Wrapper::task_spawn(int argc, char **argv) {
int ch;
int address = PCA9685_DEFAULT_ADDRESS;
int iicbus = PCA9685_DEFAULT_IICBUS;
BusCLIArguments cli{true, false};
cli.default_i2c_frequency = 400000;
cli.i2c_address = PCA9685_DEFAULT_ADDRESS;
cli.requested_bus = PCA9685_DEFAULT_IICBUS;
cli.parseDefaultArguments(argc, argv);
int32_t en_bus = 0;
param_t param_handle = param_find("PCA9685_EN_BUS");
if (param_handle != PARAM_INVALID) {
param_get(param_handle, &en_bus);
if (en_bus > 0) {
iicbus = en_bus;
}
}
int32_t i2c_addr = 0;
param_handle = param_find("PCA9685_I2C_ADDR");
if (param_handle != PARAM_INVALID) {
param_get(param_handle, &i2c_addr);
if (i2c_addr > 0) {
address = i2c_addr;
}
}
int myoptind = 1;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'a':
errno = 0;
address = strtol(myoptarg, nullptr, 16);
if (errno != 0) {
PX4_WARN("Invalid address");
return PX4_ERROR;
}
break;
case 'b':
iicbus = strtol(myoptarg, nullptr, 10);
if (errno != 0) {
PX4_WARN("Invalid bus");
return PX4_ERROR;
}
break;
case '?':
PX4_WARN("Unsupported args");
return PX4_ERROR;
default:
break;
}
}
auto *instance = new PCA9685Wrapper();
auto *instance = new PCA9685Wrapper();
if (instance) {
desc.object.store(instance);
desc.task_id = task_id_is_work_queue;
instance->pca9685 = new PCA9685(iicbus, address);
if(instance->pca9685==nullptr){
PX4_ERR("alloc failed");
goto driverInstanceAllocFailed;
}
instance->pca9685 = new PCA9685(cli.requested_bus, cli.i2c_address);
if (instance->init() == PX4_OK) {
return PX4_OK;
} else {
PX4_ERR("driver init failed");
delete instance->pca9685;
instance->pca9685=nullptr;
}
} else {
PX4_ERR("alloc failed");
return PX4_ERROR;
}
if(instance->pca9685==nullptr){
PX4_ERR("alloc failed");
goto driverInstanceAllocFailed;
}
if (instance->init() == PX4_OK) {
return PX4_OK;
} else {
PX4_ERR("driver init failed");
delete instance->pca9685;
instance->pca9685=nullptr;
}
} else {
PX4_ERR("alloc failed");
return PX4_ERROR;
}
driverInstanceAllocFailed:
delete instance;
desc.object.store(nullptr);
desc.task_id = -1;
return PX4_ERROR;
return PX4_ERROR;
}
void PCA9685Wrapper::updateParams() {