Browse Source

drivers: rename rpi_pwm_out to linux_pwm_out

sbg
Beat Küng 8 years ago
parent
commit
8527c8276f
  1. 2
      cmake/configs/posix_rpi_common.cmake
  2. 2
      posix-configs/rpi/px4.config
  3. 2
      posix-configs/rpi/px4_fw.config
  4. 2
      posix-configs/rpi/px4_no_shield.config
  5. 6
      src/drivers/linux_pwm_out/CMakeLists.txt
  6. 2
      src/drivers/linux_pwm_out/PCA9685.cpp
  7. 2
      src/drivers/linux_pwm_out/PCA9685.h
  8. 2
      src/drivers/linux_pwm_out/common.h
  9. 34
      src/drivers/linux_pwm_out/linux_pwm_out.cpp
  10. 2
      src/drivers/linux_pwm_out/navio_sysfs.cpp
  11. 2
      src/drivers/linux_pwm_out/navio_sysfs.h

2
cmake/configs/posix_rpi_common.cmake

@ -78,7 +78,7 @@ set(config_module_list @@ -78,7 +78,7 @@ set(config_module_list
drivers/navio_adc
drivers/navio_sysfs_rc_in
drivers/linux_gpio
drivers/rpi_pwm_out
drivers/linux_pwm_out
drivers/navio_rgbled
drivers/pwm_out_sim
drivers/rpi_rc_in

2
posix-configs/rpi/px4.config

@ -31,6 +31,6 @@ mavlink start -d /dev/ttyUSB0 @@ -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 ATTITUDE -r 50
navio_sysfs_rc_in start
rpi_pwm_out start
linux_pwm_out start
logger start -t -b 200
mavlink boot_complete

2
posix-configs/rpi/px4_fw.config

@ -29,6 +29,6 @@ mavlink stream -u 14556 -s MANUAL_CONTROL -r 10 @@ -29,6 +29,6 @@ mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
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
mavlink boot_complete

2
posix-configs/rpi/px4_no_shield.config

@ -27,6 +27,6 @@ mavlink stream -u 14556 -s ATTITUDE -r 50 @@ -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 ATTITUDE -r 50
rpi_rc_in start
rpi_pwm_out start -p pca9685
linux_pwm_out start -p pca9685
logger start -t
mavlink boot_complete

6
src/drivers/rpi_pwm_out/CMakeLists.txt → src/drivers/linux_pwm_out/CMakeLists.txt

@ -31,13 +31,13 @@ @@ -31,13 +31,13 @@
#
############################################################################
px4_add_module(
MODULE drivers__rpi_pwm_out
MAIN rpi_pwm_out
MODULE drivers__linux_pwm_out
MAIN linux_pwm_out
COMPILE_FLAGS
SRCS
PCA9685.cpp
navio_sysfs.cpp
rpi_pwm_out.cpp
linux_pwm_out.cpp
DEPENDS
platforms__common
)

2
src/drivers/rpi_pwm_out/PCA9685.cpp → src/drivers/linux_pwm_out/PCA9685.cpp

@ -53,7 +53,7 @@ @@ -53,7 +53,7 @@
#include <px4_log.h>
using namespace rpi_pwm_out;
using namespace linux_pwm_out;
void PCA9685::init(int bus, int address)
{

2
src/drivers/rpi_pwm_out/PCA9685.h → src/drivers/linux_pwm_out/PCA9685.h

@ -41,7 +41,7 @@ @@ -41,7 +41,7 @@
#include <inttypes.h>
#include "common.h"
namespace rpi_pwm_out
namespace linux_pwm_out
{
// Register Definitions

2
src/drivers/rpi_pwm_out/common.h → src/drivers/linux_pwm_out/common.h

@ -35,7 +35,7 @@ @@ -35,7 +35,7 @@
#include <stdint.h>
namespace rpi_pwm_out
namespace linux_pwm_out
{
/**

34
src/drivers/rpi_pwm_out/rpi_pwm_out.cpp → src/drivers/linux_pwm_out/linux_pwm_out.cpp

@ -55,7 +55,7 @@ @@ -55,7 +55,7 @@
#include "navio_sysfs.h"
#include "PCA9685.h"
namespace rpi_pwm_out
namespace linux_pwm_out
{
static px4_task_t _task_handle = -1;
volatile bool _task_should_exit = false;
@ -388,12 +388,12 @@ void usage() @@ -388,12 +388,12 @@ void usage()
PX4_INFO(" pwm_out status");
}
} // namespace rpi_pwm_out
} // namespace linux_pwm_out
/* 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 myoptind = 1;
@ -411,15 +411,15 @@ int rpi_pwm_out_main(int argc, char *argv[]) @@ -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) {
switch (ch) {
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;
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;
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;
case 'n': {
@ -433,44 +433,44 @@ int rpi_pwm_out_main(int argc, char *argv[]) @@ -433,44 +433,44 @@ int rpi_pwm_out_main(int argc, char *argv[])
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;
}
}
// gets the parameters for the esc's pwm
param_get(param_find("PWM_DISARMED"), &rpi_pwm_out::_pwm_disarmed);
param_get(param_find("PWM_MIN"), &rpi_pwm_out::_pwm_min);
param_get(param_find("PWM_MAX"), &rpi_pwm_out::_pwm_max);
param_get(param_find("PWM_DISARMED"), &linux_pwm_out::_pwm_disarmed);
param_get(param_find("PWM_MIN"), &linux_pwm_out::_pwm_min);
param_get(param_find("PWM_MAX"), &linux_pwm_out::_pwm_max);
/*
* Start/load the driver.
*/
if (!strcmp(verb, "start")) {
if (rpi_pwm_out::_is_running) {
if (linux_pwm_out::_is_running) {
PX4_WARN("pwm_out already running");
return 1;
}
rpi_pwm_out::start();
linux_pwm_out::start();
}
else if (!strcmp(verb, "stop")) {
if (!rpi_pwm_out::_is_running) {
if (!linux_pwm_out::_is_running) {
PX4_WARN("pwm_out is not running");
return 1;
}
rpi_pwm_out::stop();
linux_pwm_out::stop();
}
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;
} else {
rpi_pwm_out::usage();
linux_pwm_out::usage();
return 1;
}

2
src/drivers/rpi_pwm_out/navio_sysfs.cpp → src/drivers/linux_pwm_out/navio_sysfs.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <errno.h>
#include <px4_log.h>
using namespace rpi_pwm_out;
using namespace linux_pwm_out;
NavioSysfsPWMOut::NavioSysfsPWMOut(const char *device, int max_num_outputs)
: _device(device)

2
src/drivers/rpi_pwm_out/navio_sysfs.h → src/drivers/linux_pwm_out/navio_sysfs.h

@ -35,7 +35,7 @@ @@ -35,7 +35,7 @@
#include "common.h"
namespace rpi_pwm_out
namespace linux_pwm_out
{
/**
Loading…
Cancel
Save