mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 13:15:08 +08:00
drivers: rename rpi_pwm_out to linux_pwm_out
This commit is contained in:
@@ -78,7 +78,7 @@ set(config_module_list
|
|||||||
drivers/navio_adc
|
drivers/navio_adc
|
||||||
drivers/navio_sysfs_rc_in
|
drivers/navio_sysfs_rc_in
|
||||||
drivers/linux_gpio
|
drivers/linux_gpio
|
||||||
drivers/rpi_pwm_out
|
drivers/linux_pwm_out
|
||||||
drivers/navio_rgbled
|
drivers/navio_rgbled
|
||||||
drivers/pwm_out_sim
|
drivers/pwm_out_sim
|
||||||
drivers/rpi_rc_in
|
drivers/rpi_rc_in
|
||||||
|
|||||||
@@ -31,6 +31,6 @@ mavlink start -d /dev/ttyUSB0
|
|||||||
mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
||||||
mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
||||||
navio_sysfs_rc_in start
|
navio_sysfs_rc_in start
|
||||||
rpi_pwm_out start
|
linux_pwm_out start
|
||||||
logger start -t -b 200
|
logger start -t -b 200
|
||||||
mavlink boot_complete
|
mavlink boot_complete
|
||||||
|
|||||||
@@ -29,6 +29,6 @@ mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
|
|||||||
|
|
||||||
|
|
||||||
navio_sysfs_rc_in start
|
navio_sysfs_rc_in start
|
||||||
rpi_pwm_out start -m ROMFS/px4fmu_common/mixers/AERT.main.mix
|
linux_pwm_out start -m ROMFS/px4fmu_common/mixers/AERT.main.mix
|
||||||
logger start -t -b 200
|
logger start -t -b 200
|
||||||
mavlink boot_complete
|
mavlink boot_complete
|
||||||
|
|||||||
@@ -27,6 +27,6 @@ mavlink stream -u 14556 -s ATTITUDE -r 50
|
|||||||
#mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
#mavlink stream -d /dev/ttyUSB0 -s HIGHRES_IMU -r 50
|
||||||
#mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
#mavlink stream -d /dev/ttyUSB0 -s ATTITUDE -r 50
|
||||||
rpi_rc_in start
|
rpi_rc_in start
|
||||||
rpi_pwm_out start -p pca9685
|
linux_pwm_out start -p pca9685
|
||||||
logger start -t
|
logger start -t
|
||||||
mavlink boot_complete
|
mavlink boot_complete
|
||||||
|
|||||||
@@ -31,13 +31,13 @@
|
|||||||
#
|
#
|
||||||
############################################################################
|
############################################################################
|
||||||
px4_add_module(
|
px4_add_module(
|
||||||
MODULE drivers__rpi_pwm_out
|
MODULE drivers__linux_pwm_out
|
||||||
MAIN rpi_pwm_out
|
MAIN linux_pwm_out
|
||||||
COMPILE_FLAGS
|
COMPILE_FLAGS
|
||||||
SRCS
|
SRCS
|
||||||
PCA9685.cpp
|
PCA9685.cpp
|
||||||
navio_sysfs.cpp
|
navio_sysfs.cpp
|
||||||
rpi_pwm_out.cpp
|
linux_pwm_out.cpp
|
||||||
DEPENDS
|
DEPENDS
|
||||||
platforms__common
|
platforms__common
|
||||||
)
|
)
|
||||||
@@ -53,7 +53,7 @@
|
|||||||
|
|
||||||
#include <px4_log.h>
|
#include <px4_log.h>
|
||||||
|
|
||||||
using namespace rpi_pwm_out;
|
using namespace linux_pwm_out;
|
||||||
|
|
||||||
void PCA9685::init(int bus, int address)
|
void PCA9685::init(int bus, int address)
|
||||||
{
|
{
|
||||||
@@ -41,7 +41,7 @@
|
|||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include "common.h"
|
#include "common.h"
|
||||||
|
|
||||||
namespace rpi_pwm_out
|
namespace linux_pwm_out
|
||||||
{
|
{
|
||||||
|
|
||||||
// Register Definitions
|
// Register Definitions
|
||||||
@@ -35,7 +35,7 @@
|
|||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
namespace rpi_pwm_out
|
namespace linux_pwm_out
|
||||||
{
|
{
|
||||||
|
|
||||||
/**
|
/**
|
||||||
+17
-17
@@ -55,7 +55,7 @@
|
|||||||
#include "navio_sysfs.h"
|
#include "navio_sysfs.h"
|
||||||
#include "PCA9685.h"
|
#include "PCA9685.h"
|
||||||
|
|
||||||
namespace rpi_pwm_out
|
namespace linux_pwm_out
|
||||||
{
|
{
|
||||||
static px4_task_t _task_handle = -1;
|
static px4_task_t _task_handle = -1;
|
||||||
volatile bool _task_should_exit = false;
|
volatile bool _task_should_exit = false;
|
||||||
@@ -388,12 +388,12 @@ void usage()
|
|||||||
PX4_INFO(" pwm_out status");
|
PX4_INFO(" pwm_out status");
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace rpi_pwm_out
|
} // namespace linux_pwm_out
|
||||||
|
|
||||||
/* driver 'main' command */
|
/* driver 'main' command */
|
||||||
extern "C" __EXPORT int rpi_pwm_out_main(int argc, char *argv[]);
|
extern "C" __EXPORT int linux_pwm_out_main(int argc, char *argv[]);
|
||||||
|
|
||||||
int rpi_pwm_out_main(int argc, char *argv[])
|
int linux_pwm_out_main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
int ch;
|
int ch;
|
||||||
int myoptind = 1;
|
int myoptind = 1;
|
||||||
@@ -411,15 +411,15 @@ int rpi_pwm_out_main(int argc, char *argv[])
|
|||||||
while ((ch = px4_getopt(argc, argv, "d:m:p:n:", &myoptind, &myoptarg)) != EOF) {
|
while ((ch = px4_getopt(argc, argv, "d:m:p:n:", &myoptind, &myoptarg)) != EOF) {
|
||||||
switch (ch) {
|
switch (ch) {
|
||||||
case 'd':
|
case 'd':
|
||||||
strncpy(rpi_pwm_out::_device, myoptarg, sizeof(rpi_pwm_out::_device));
|
strncpy(linux_pwm_out::_device, myoptarg, sizeof(linux_pwm_out::_device));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'm':
|
case 'm':
|
||||||
strncpy(rpi_pwm_out::_mixer_filename, myoptarg, sizeof(rpi_pwm_out::_mixer_filename));
|
strncpy(linux_pwm_out::_mixer_filename, myoptarg, sizeof(linux_pwm_out::_mixer_filename));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'p':
|
case 'p':
|
||||||
strncpy(rpi_pwm_out::_protocol, myoptarg, sizeof(rpi_pwm_out::_protocol));
|
strncpy(linux_pwm_out::_protocol, myoptarg, sizeof(linux_pwm_out::_protocol));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'n': {
|
case 'n': {
|
||||||
@@ -433,44 +433,44 @@ int rpi_pwm_out_main(int argc, char *argv[])
|
|||||||
max_num = actuator_outputs_s::NUM_ACTUATOR_OUTPUTS;
|
max_num = actuator_outputs_s::NUM_ACTUATOR_OUTPUTS;
|
||||||
}
|
}
|
||||||
|
|
||||||
rpi_pwm_out::_max_mum_outputs = max_num;
|
linux_pwm_out::_max_mum_outputs = max_num;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// gets the parameters for the esc's pwm
|
// gets the parameters for the esc's pwm
|
||||||
param_get(param_find("PWM_DISARMED"), &rpi_pwm_out::_pwm_disarmed);
|
param_get(param_find("PWM_DISARMED"), &linux_pwm_out::_pwm_disarmed);
|
||||||
param_get(param_find("PWM_MIN"), &rpi_pwm_out::_pwm_min);
|
param_get(param_find("PWM_MIN"), &linux_pwm_out::_pwm_min);
|
||||||
param_get(param_find("PWM_MAX"), &rpi_pwm_out::_pwm_max);
|
param_get(param_find("PWM_MAX"), &linux_pwm_out::_pwm_max);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Start/load the driver.
|
* Start/load the driver.
|
||||||
*/
|
*/
|
||||||
if (!strcmp(verb, "start")) {
|
if (!strcmp(verb, "start")) {
|
||||||
if (rpi_pwm_out::_is_running) {
|
if (linux_pwm_out::_is_running) {
|
||||||
PX4_WARN("pwm_out already running");
|
PX4_WARN("pwm_out already running");
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
rpi_pwm_out::start();
|
linux_pwm_out::start();
|
||||||
}
|
}
|
||||||
|
|
||||||
else if (!strcmp(verb, "stop")) {
|
else if (!strcmp(verb, "stop")) {
|
||||||
if (!rpi_pwm_out::_is_running) {
|
if (!linux_pwm_out::_is_running) {
|
||||||
PX4_WARN("pwm_out is not running");
|
PX4_WARN("pwm_out is not running");
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
rpi_pwm_out::stop();
|
linux_pwm_out::stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
else if (!strcmp(verb, "status")) {
|
else if (!strcmp(verb, "status")) {
|
||||||
PX4_WARN("pwm_out is %s", rpi_pwm_out::_is_running ? "running" : "not running");
|
PX4_WARN("pwm_out is %s", linux_pwm_out::_is_running ? "running" : "not running");
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
rpi_pwm_out::usage();
|
linux_pwm_out::usage();
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -37,7 +37,7 @@
|
|||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
#include <px4_log.h>
|
#include <px4_log.h>
|
||||||
|
|
||||||
using namespace rpi_pwm_out;
|
using namespace linux_pwm_out;
|
||||||
|
|
||||||
NavioSysfsPWMOut::NavioSysfsPWMOut(const char *device, int max_num_outputs)
|
NavioSysfsPWMOut::NavioSysfsPWMOut(const char *device, int max_num_outputs)
|
||||||
: _device(device)
|
: _device(device)
|
||||||
@@ -35,7 +35,7 @@
|
|||||||
|
|
||||||
#include "common.h"
|
#include "common.h"
|
||||||
|
|
||||||
namespace rpi_pwm_out
|
namespace linux_pwm_out
|
||||||
{
|
{
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Reference in New Issue
Block a user