Browse Source

tap_esc: converted to module

sbg
Alessandro Simovic 7 years ago committed by Beat Küng
parent
commit
b71ac78959
  1. 373
      src/drivers/tap_esc/tap_esc.cpp

373
src/drivers/tap_esc/tap_esc.cpp

@ -33,6 +33,8 @@
#include <stdint.h> #include <stdint.h>
#include <px4_defines.h>
#include <px4_module.h>
#include <px4_tasks.h> #include <px4_tasks.h>
#include <px4_getopt.h> #include <px4_getopt.h>
#include <px4_posix.h> #include <px4_posix.h>
@ -71,11 +73,15 @@
# define BOARD_TAP_ESC_MODE 0 # define BOARD_TAP_ESC_MODE 0
#endif #endif
#if !defined(DEVICE_ARGUMENT_MAX_LENGTH)
# define DEVICE_ARGUMENT_MAX_LENGTH 32
#endif
/* /*
* This driver connects to TAP ESCs via serial. * This driver connects to TAP ESCs via serial.
*/ */
class TAP_ESC : public device::CDev, public ModuleParams class TAP_ESC : public device::CDev, public ModuleBase<TAP_ESC>, public ModuleParams
{ {
public: public:
enum Mode { enum Mode {
@ -91,15 +97,31 @@ public:
MODE_5CAP, MODE_5CAP,
MODE_6CAP, MODE_6CAP,
}; };
TAP_ESC(int channels_count, int uart_fd); TAP_ESC();
virtual ~TAP_ESC(); virtual ~TAP_ESC();
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static TAP_ESC *instantiate(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
/** @see ModuleBase::run() */
void run() override;
virtual int init(); virtual int init();
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg); virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
void cycle(); void cycle();
private: private:
static char _device[DEVICE_ARGUMENT_MAX_LENGTH];
int _uart_fd; int _uart_fd;
static const uint8_t device_mux_map[TAP_ESC_MAX_MOTOR_NUM]; static const uint8_t device_mux_map[TAP_ESC_MAX_MOTOR_NUM];
static const uint8_t device_dir_map[TAP_ESC_MAX_MOTOR_NUM]; static const uint8_t device_dir_map[TAP_ESC_MAX_MOTOR_NUM];
@ -128,7 +150,7 @@ private:
orb_advert_t _esc_feedback_pub = nullptr; orb_advert_t _esc_feedback_pub = nullptr;
orb_advert_t _to_mixer_status; ///< mixer status flags orb_advert_t _to_mixer_status; ///< mixer status flags
esc_status_s _esc_feedback; esc_status_s _esc_feedback;
uint8_t _channels_count; // The number of ESC channels static uint8_t _channels_count; // The number of ESC channels
MixerGroup *_mixers; MixerGroup *_mixers;
uint32_t _groups_required; uint32_t _groups_required;
@ -146,8 +168,6 @@ private:
void subscribe(); void subscribe();
void work_start();
void work_stop();
void send_esc_outputs(const uint16_t *pwm, const unsigned num_pwm); void send_esc_outputs(const uint16_t *pwm, const unsigned num_pwm);
static int control_callback_trampoline(uintptr_t handle, static int control_callback_trampoline(uintptr_t handle,
@ -157,18 +177,15 @@ private:
const uint8_t TAP_ESC::device_mux_map[TAP_ESC_MAX_MOTOR_NUM] = ESC_POS; const uint8_t TAP_ESC::device_mux_map[TAP_ESC_MAX_MOTOR_NUM] = ESC_POS;
const uint8_t TAP_ESC::device_dir_map[TAP_ESC_MAX_MOTOR_NUM] = ESC_DIR; const uint8_t TAP_ESC::device_dir_map[TAP_ESC_MAX_MOTOR_NUM] = ESC_DIR;
char TAP_ESC::_device[DEVICE_ARGUMENT_MAX_LENGTH] = {};
namespace uint8_t TAP_ESC::_channels_count = 0;
{
TAP_ESC *tap_esc = nullptr;
}
# define TAP_ESC_DEVICE_PATH "/dev/tap_esc" # define TAP_ESC_DEVICE_PATH "/dev/tap_esc"
TAP_ESC::TAP_ESC(int channels_count, int uart_fd): TAP_ESC::TAP_ESC():
CDev("tap_esc", TAP_ESC_DEVICE_PATH), CDev("tap_esc", TAP_ESC_DEVICE_PATH),
ModuleParams(nullptr), ModuleParams(nullptr),
_uart_fd(uart_fd), _uart_fd(-1),
_is_armed(false), _is_armed(false),
_poll_fds_num(0), _poll_fds_num(0),
_mode(MODE_4PWM), //FIXME: what is this mode used for??? _mode(MODE_4PWM), //FIXME: what is this mode used for???
@ -180,7 +197,6 @@ TAP_ESC::TAP_ESC(int channels_count, int uart_fd):
_esc_feedback_pub(nullptr), _esc_feedback_pub(nullptr),
_to_mixer_status(nullptr), _to_mixer_status(nullptr),
_esc_feedback{}, _esc_feedback{},
_channels_count(channels_count),
_mixers(nullptr), _mixers(nullptr),
_groups_required(0), _groups_required(0),
_groups_subscribed(0), _groups_subscribed(0),
@ -214,25 +230,53 @@ TAP_ESC::TAP_ESC(int channels_count, int uart_fd):
TAP_ESC::~TAP_ESC() TAP_ESC::~TAP_ESC()
{ {
if (_initialized) { if (_initialized) {
/* tell the task we want it to go away */ for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
work_stop(); if (_control_subs[i] >= 0) {
orb_unsubscribe(_control_subs[i]);
_control_subs[i] = -1;
}
}
orb_unsubscribe(_armed_sub);
_armed_sub = -1;
orb_unsubscribe(_test_motor_sub);
_test_motor_sub = -1;
orb_unsubscribe(_params_sub);
int i = 10; orb_unadvertise(_outputs_pub);
orb_unadvertise(_esc_feedback_pub);
orb_unadvertise(_to_mixer_status);
do { tap_esc_common::deinitialise_uart(_uart_fd);
/* wait 50ms - it should wake every 100ms or so worst-case */
usleep(50000);
i--;
} while (_initialized && i > 0); DEVICE_LOG("stopping");
_initialized = false;
} }
}
/** @see ModuleBase */
TAP_ESC *
TAP_ESC::instantiate(int argc, char *argv[])
{
TAP_ESC *tap_esc = new TAP_ESC();
// clean up the alternate device node if (tap_esc->init() != 0) {
//unregister_class_devname(PWM_OUTPUT_BASE_DEVICE_PATH, _class_instance); PX4_ERR("failed to initialize module");
delete tap_esc;
return nullptr;
}
tap_esc = nullptr; return tap_esc;
} }
/** @see ModuleBase */
int
TAP_ESC::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int int
TAP_ESC::init() TAP_ESC::init()
{ {
@ -240,6 +284,13 @@ TAP_ESC::init()
ASSERT(!_initialized); ASSERT(!_initialized);
ret = tap_esc_common::initialise_uart(_device, _uart_fd);
if (ret < 0) {
PX4_ERR("failed to initialise UART.");
return ret;
}
/* Respect boot time required by the ESC FW */ /* Respect boot time required by the ESC FW */
hrt_abstime uptime_us = hrt_absolute_time(); hrt_abstime uptime_us = hrt_absolute_time();
@ -659,25 +710,6 @@ TAP_ESC::cycle()
} }
void TAP_ESC::work_stop()
{
for (unsigned i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
if (_control_subs[i] >= 0) {
orb_unsubscribe(_control_subs[i]);
_control_subs[i] = -1;
}
}
orb_unsubscribe(_armed_sub);
_armed_sub = -1;
orb_unsubscribe(_test_motor_sub);
_test_motor_sub = -1;
orb_unsubscribe(_params_sub);
DEVICE_LOG("stopping");
_initialized = false;
}
int TAP_ESC::control_callback_trampoline(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input) int TAP_ESC::control_callback_trampoline(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input)
{ {
TAP_ESC *obj = (TAP_ESC *)handle; TAP_ESC *obj = (TAP_ESC *)handle;
@ -779,214 +811,121 @@ TAP_ESC::ioctl(device::file_t *filp, int cmd, unsigned long arg)
return ret; return ret;
} }
namespace tap_esc_drv /** @see ModuleBase */
void TAP_ESC::run()
{ {
volatile bool _task_should_exit = false; // flag indicating if tap_esc task should exit // Main loop
static int _uart_fd = -1; while (!should_exit()) {
static char _device[32] = {}; cycle();
static bool _is_running = false; // flag indicating if tap_esc app is running
static px4_task_t _task_handle = -1; // handle to the task main thread
static int _supported_channel_count = 0;
void usage();
void start();
void stop();
int tap_esc_start(void);
int tap_esc_stop(void);
void task_main_trampoline(int argc, char *argv[]);
void task_main(int argc, char *argv[]);
int tap_esc_start(void)
{
int ret = OK;
if (tap_esc == nullptr) {
tap_esc = new TAP_ESC(_supported_channel_count, _uart_fd);
if (tap_esc == nullptr) {
ret = -ENOMEM;
} else {
ret = tap_esc->init();
if (ret != OK) {
PX4_ERR("failed to initialize tap_esc (%i)", ret);
delete tap_esc;
tap_esc = nullptr;
}
}
} }
return ret;
} }
int tap_esc_stop(void) /** @see ModuleBase */
int TAP_ESC::task_spawn(int argc, char *argv[])
{ {
int ret = OK; /* Parse arguments */
const char *device = nullptr;
bool error_flag = false;
if (tap_esc != nullptr) { int ch;
int myoptind = 1;
const char *myoptarg = nullptr;
delete tap_esc; if (argc < 2) {
tap_esc = nullptr; print_usage("not enough arguments");
error_flag = true;
} }
return ret; while ((ch = px4_getopt(argc, argv, "d:n:", &myoptind, &myoptarg)) != EOF) {
} switch (ch) {
case 'd':
device = myoptarg;
void task_main(int argc, char *argv[]) strncpy(_device, device, sizeof(_device));
{
_is_running = true;
if (tap_esc_common::initialise_uart(_device, _uart_fd) < 0) { // Fix in case of overflow
PX4_ERR("Failed to initialize UART."); _device[sizeof(_device) - 1] = '\0';
break;
while (_task_should_exit == false) { case 'n':
usleep(100000); _channels_count = atoi(myoptarg);
break;
} }
_is_running = false;
return;
} }
if (tap_esc_start() != OK) { if (error_flag) {
PX4_ERR("failed to start tap_esc."); return -1;
_is_running = false;
return;
} }
/* Sanity check on arguments */
// Main loop if (_channels_count == 0) {
while (!_task_should_exit) { print_usage("Channel count is invalid (0)");
return PX4_ERROR;
tap_esc->cycle();
} }
if (device == nullptr || strlen(device) == 0) {
_is_running = false; print_usage("no device psecified");
} return PX4_ERROR;
}
void task_main_trampoline(int argc, char *argv[])
{
task_main(argc, argv);
}
void start()
{
ASSERT(_task_handle == -1);
_task_should_exit = false;
/* start the task */ /* start the task */
_task_handle = px4_task_spawn_cmd("tap_esc", _task_id = px4_task_spawn_cmd("tap_esc",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_ACTUATOR_OUTPUTS, SCHED_PRIORITY_ACTUATOR_OUTPUTS,
1100, 1100,
(px4_main_t)&task_main_trampoline, (px4_main_t)&run_trampoline,
nullptr); nullptr);
if (_task_handle < 0) { if (_task_id < 0) {
PX4_ERR("task start failed"); PX4_ERR("task start failed");
_task_handle = -1; _task_id = -1;
return; return PX4_ERROR;
} }
}
void stop()
{
_task_should_exit = true;
while (_is_running) { // wait until task is up & running
usleep(200000); if (wait_until_running() < 0) {
PX4_INFO("tap_esc_stop"); _task_id = -1;
return -1;
} }
tap_esc_stop(); return PX4_OK;
tap_esc_common::deinitialise_uart(_uart_fd);
_task_handle = -1;
} }
void usage() /** @see ModuleBase */
{ int
PX4_INFO("usage: tap_esc start -d /dev/ttyS2 -n <1-8>"); TAP_ESC::print_usage(const char *reason)
PX4_INFO(" tap_esc stop");
PX4_INFO(" tap_esc status");
}
} // namespace tap_esc
// driver 'main' command
extern "C" __EXPORT int tap_esc_main(int argc, char *argv[]);
int tap_esc_main(int argc, char *argv[])
{ {
const char *device = nullptr; if (reason) {
int ch; PX4_WARN("%s\n", reason);
int myoptind = 1;
const char *myoptarg = nullptr;
char *verb = nullptr;
if (argc >= 2) {
verb = argv[1];
} }
while ((ch = px4_getopt(argc, argv, "d:n:", &myoptind, &myoptarg)) != EOF) { PRINT_MODULE_DESCRIPTION(
switch (ch) { R"DESCR_STR(
case 'd': ### Description
device = myoptarg; This module controls the TAP_ESC hardware via UART. It listens on the
strncpy(tap_esc_drv::_device, device, strlen(device)); actuator_controls topics, does the mixing and writes the PWM outputs.
break;
case 'n': ### Implementation
tap_esc_drv::_supported_channel_count = atoi(myoptarg); Currently the module is implementd as a threaded version only, meaning that it
break; runs in its own thread instead of on the work queue.
}
}
if (!tap_esc && tap_esc_drv::_task_handle != -1) {
tap_esc_drv::_task_handle = -1;
}
// Start/load the driver.
if (!strcmp(verb, "start")) {
if (tap_esc_drv::_is_running) {
PX4_WARN("tap_esc already running");
return 1;
}
// Check on required arguments
if (tap_esc_drv::_supported_channel_count == 0 || device == nullptr || strlen(device) == 0) {
tap_esc_drv::usage();
return 1;
}
tap_esc_drv::start(); ### Example
} The module is typically started with:
tap_esc start -d /dev/ttyS2 -n <1-8>
else if (!strcmp(verb, "stop")) { )DESCR_STR");
if (!tap_esc_drv::_is_running) {
PX4_WARN("tap_esc is not running");
return 1;
}
tap_esc_drv::stop(); PRINT_MODULE_USAGE_NAME("tap_esc", "driver");
}
else if (!strcmp(verb, "status")) { PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task");
PX4_WARN("tap_esc is %s", tap_esc_drv::_is_running ? "running" : "not running"); PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "<device>", "Device used to talk to ESCs", true);
return 0; PRINT_MODULE_USAGE_PARAM_INT('n', 4, 0, 8, "Number of ESCs", true);
return PX4_OK;
}
} else { extern "C" __EXPORT int tap_esc_main(int argc, char *argv[]);
tap_esc_drv::usage();
return 1;
}
return 0; int
tap_esc_main(int argc, char *argv[])
{
return TAP_ESC::main(argc, argv);
} }

Loading…
Cancel
Save