aboutsummaryrefslogtreecommitdiff
path: root/apps/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'apps/drivers')
-rw-r--r--apps/drivers/boards/px4io/px4io_internal.h22
-rw-r--r--apps/drivers/drv_mixer.h23
-rw-r--r--apps/drivers/hil/hil.cpp23
-rw-r--r--apps/drivers/px4fmu/fmu.cpp22
-rw-r--r--apps/drivers/px4io/px4io.cpp187
-rw-r--r--apps/drivers/px4io/uploader.cpp1
6 files changed, 132 insertions, 146 deletions
diff --git a/apps/drivers/boards/px4io/px4io_internal.h b/apps/drivers/boards/px4io/px4io_internal.h
index a0342ac8a..3ac8a5cfa 100644
--- a/apps/drivers/boards/px4io/px4io_internal.h
+++ b/apps/drivers/boards/px4io/px4io_internal.h
@@ -61,28 +61,6 @@
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
-/* R/C in/out channels **************************************************************/
-
-/* XXX just GPIOs for now - eventually timer pins */
-
-#define GPIO_CH1_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_CH2_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_CH3_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8)
-#define GPIO_CH4_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
-#define GPIO_CH5_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
-#define GPIO_CH6_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
-#define GPIO_CH7_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
-#define GPIO_CH8_IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
-
-#define GPIO_CH1_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_CH2_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_CH3_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
-#define GPIO_CH4_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
-#define GPIO_CH5_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN6)
-#define GPIO_CH6_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7)
-#define GPIO_CH7_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
-#define GPIO_CH8_OUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
-
/* Safety switch button *************************************************************/
#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
diff --git a/apps/drivers/drv_mixer.h b/apps/drivers/drv_mixer.h
index 793e86b32..9f43015d9 100644
--- a/apps/drivers/drv_mixer.h
+++ b/apps/drivers/drv_mixer.h
@@ -100,28 +100,13 @@ struct mixer_simple_s {
*/
#define MIXERIOCADDSIMPLE _MIXERIOC(2)
-/** multirotor output definition */
-struct mixer_rotor_output_s {
- float angle; /**< rotor angle clockwise from forward in radians */
- float distance; /**< motor distance from centre in arbitrary units */
-};
-
-/** multirotor mixer */
-struct mixer_multirotor_s {
- uint8_t rotor_count;
- struct mixer_control_s controls[4]; /**< controls are roll, pitch, yaw, thrust */
- struct mixer_rotor_output_s rotors[0]; /**< actual size of the array is set by rotor_count */
-};
-
-/**
- * Add a multirotor mixer in (struct mixer_multirotor_s *)arg
- */
-#define MIXERIOCADDMULTIROTOR _MIXERIOC(3)
+/* _MIXERIOC(3) was deprecated */
+/* _MIXERIOC(4) was deprecated */
/**
- * Add mixers(s) from a the file in (const char *)arg
+ * Add mixer(s) from the buffer in (const char *)arg
*/
-#define MIXERIOCLOADFILE _MIXERIOC(4)
+#define MIXERIOCLOADBUF _MIXERIOC(5)
/*
* XXX Thoughts for additional operations:
diff --git a/apps/drivers/hil/hil.cpp b/apps/drivers/hil/hil.cpp
index 67b16aa42..f227db1f7 100644
--- a/apps/drivers/hil/hil.cpp
+++ b/apps/drivers/hil/hil.cpp
@@ -577,26 +577,19 @@ HIL::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
- case MIXERIOCADDMULTIROTOR:
- /* XXX not yet supported */
- ret = -ENOTTY;
- break;
+ case MIXERIOCLOADBUF: {
+ const char *buf = (const char *)arg;
+ unsigned buflen = strnlen(buf, 1024);
- case MIXERIOCLOADFILE: {
- const char *path = (const char *)arg;
-
- if (_mixers != nullptr) {
- delete _mixers;
- _mixers = nullptr;
- }
+ if (_mixers == nullptr)
+ _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
- _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
if (_mixers == nullptr) {
ret = -ENOMEM;
+
} else {
- debug("loading mixers from %s", path);
- ret = _mixers->load_from_file(path);
+ ret = _mixers->load_from_buf(buf, buflen);
if (ret != 0) {
debug("mixer load failed with %d", ret);
@@ -605,10 +598,10 @@ HIL::pwm_ioctl(file *filp, int cmd, unsigned long arg)
ret = -EINVAL;
}
}
-
break;
}
+
default:
ret = -ENOTTY;
break;
diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp
index 2e3b130a9..819dbf208 100644
--- a/apps/drivers/px4fmu/fmu.cpp
+++ b/apps/drivers/px4fmu/fmu.cpp
@@ -544,28 +544,19 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
- case MIXERIOCADDMULTIROTOR:
- /* XXX not yet supported */
- ret = -ENOTTY;
- break;
+ case MIXERIOCLOADBUF: {
+ const char *buf = (const char *)arg;
+ unsigned buflen = strnlen(buf, 1024);
- case MIXERIOCLOADFILE: {
- const char *path = (const char *)arg;
-
- if (_mixers != nullptr) {
- delete _mixers;
- _mixers = nullptr;
- }
-
- _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
+ if (_mixers == nullptr)
+ _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
if (_mixers == nullptr) {
ret = -ENOMEM;
} else {
- debug("loading mixers from %s", path);
- ret = _mixers->load_from_file(path);
+ ret = _mixers->load_from_buf(buf, buflen);
if (ret != 0) {
debug("mixer load failed with %d", ret);
@@ -574,7 +565,6 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
ret = -EINVAL;
}
}
-
break;
}
diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp
index f32f9a105..c1b52b07b 100644
--- a/apps/drivers/px4io/px4io.cpp
+++ b/apps/drivers/px4io/px4io.cpp
@@ -92,7 +92,7 @@ public:
bool dump_one;
private:
- static const unsigned _max_actuators = PX4IO_OUTPUT_CHANNELS;
+ static const unsigned _max_actuators = PX4IO_CONTROL_CHANNELS;
int _serial_fd; ///< serial interface to PX4IO
hx_stream_t _io_stream; ///< HX protocol stream
@@ -113,7 +113,8 @@ private:
orb_advert_t _t_outputs; ///< mixed outputs topic
actuator_outputs_s _outputs; ///< mixed outputs
- MixerGroup *_mixers; ///< loaded mixers
+ const char *volatile _mix_buf; ///< mixer text buffer
+ volatile unsigned _mix_buf_len; ///< size of the mixer text buffer
bool _primary_pwm_device; ///< true if we are the default PWM output
@@ -161,6 +162,11 @@ private:
void config_send();
/**
+ * Send a buffer containing mixer text to PX4IO
+ */
+ int mixer_send(const char *buf, unsigned buflen);
+
+ /**
* Mixer control callback; invoked to fetch a control from a specific
* group/index during mixing.
*/
@@ -189,7 +195,8 @@ PX4IO::PX4IO() :
_t_actuators(-1),
_t_armed(-1),
_t_outputs(-1),
- _mixers(nullptr),
+ _mix_buf(nullptr),
+ _mix_buf_len(0),
_primary_pwm_device(false),
_relays(0),
_switch_armed(false),
@@ -212,6 +219,7 @@ PX4IO::~PX4IO()
/* give it another 100ms */
usleep(100000);
}
+
/* well, kill it anyway, though this will probably crash */
if (_task != -1)
task_delete(_task);
@@ -242,6 +250,7 @@ PX4IO::init()
/* start the IO interface task */
_task = task_create("px4io", SCHED_PRIORITY_DEFAULT, 4096, (main_t)&PX4IO::task_main_trampoline, nullptr);
+
if (_task < 0) {
debug("task start failed: %d", errno);
return -errno;
@@ -253,13 +262,16 @@ PX4IO::init()
debug("PX4IO connected");
break;
}
+
usleep(100000);
}
+
if (!_connected) {
/* error here will result in everything being torn down */
log("PX4IO not responding");
return -EIO;
}
+
return OK;
}
@@ -272,7 +284,7 @@ PX4IO::task_main_trampoline(int argc, char *argv[])
void
PX4IO::task_main()
{
- log("starting");
+ debug("starting");
/* open the serial port */
_serial_fd = ::open("/dev/ttyS2", O_RDWR);
@@ -294,10 +306,12 @@ PX4IO::task_main()
/* protocol stream */
_io_stream = hx_stream_init(_serial_fd, &PX4IO::rx_callback_trampoline, this);
+
if (_io_stream == nullptr) {
log("failed to allocate HX protocol stream");
goto out;
}
+
hx_stream_set_counters(_io_stream,
perf_alloc(PC_COUNT, "PX4IO frames transmitted"),
perf_alloc(PC_COUNT, "PX4IO frames received"),
@@ -334,13 +348,18 @@ PX4IO::task_main()
fds[2].fd = _t_armed;
fds[2].events = POLLIN;
- log("ready");
+ debug("ready");
+
+ /* lock against the ioctl handler */
+ lock();
/* loop handling received serial bytes */
while (!_task_should_exit) {
/* sleep waiting for data, but no more than 100ms */
+ unlock();
int ret = ::poll(&fds[0], sizeof(fds) / sizeof(fds[0]), 100);
+ lock();
/* this would be bad... */
if (ret < 0) {
@@ -357,26 +376,21 @@ PX4IO::task_main()
if (fds[0].revents & POLLIN)
io_recv();
- /* if we have new data from the ORB, go handle it */
+ /* if we have new control data from the ORB, handle it */
if (fds[1].revents & POLLIN) {
/* get controls */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
- /* mix */
- if (_mixers != nullptr) {
- /* XXX is this the right count? */
- _mixers->mix(&_outputs.output[0], _max_actuators);
-
- /* convert to PWM values */
- for (unsigned i = 0; i < _max_actuators; i++)
- _outputs.output[i] = 1500 + (600 * _outputs.output[i]);
+ /* scale controls to PWM (temporary measure) */
+ for (unsigned i = 0; i < _max_actuators; i++)
+ _outputs.output[i] = 1500 + (600 * _controls.control[i]);
- /* and flag for update */
- _send_needed = true;
- }
+ /* and flag for update */
+ _send_needed = true;
}
+ /* if we have an arming state update, handle it */
if (fds[2].revents & POLLIN) {
orb_copy(ORB_ID(actuator_armed), _t_armed, &_armed);
@@ -395,14 +409,26 @@ PX4IO::task_main()
_config_needed = false;
config_send();
}
+
+ /* send a mixer update if needed */
+ if (_mix_buf != nullptr) {
+ mixer_send(_mix_buf, _mix_buf_len);
+
+ /* clear the buffer record so the ioctl handler knows we're done */
+ _mix_buf = nullptr;
+ _mix_buf_len = 0;
+ }
}
+ unlock();
+
out:
debug("exiting");
/* kill the HX stream */
if (_io_stream != nullptr)
hx_stream_free(_io_stream);
+
::close(_serial_fd);
/* clean up the alternate device node */
@@ -455,25 +481,27 @@ PX4IO::rx_callback(const uint8_t *buffer, size_t bytes_received)
{
const px4io_report *rep = (const px4io_report *)buffer;
- lock();
+// lock();
/* sanity-check the received frame size */
if (bytes_received != sizeof(px4io_report)) {
debug("got %u expected %u", bytes_received, sizeof(px4io_report));
goto out;
}
+
if (rep->i2f_magic != I2F_MAGIC) {
debug("bad magic");
goto out;
}
+
_connected = true;
/* publish raw rc channel values from IO if valid channels are present */
if (rep->channel_count > 0) {
_input_rc.timestamp = hrt_absolute_time();
_input_rc.channel_count = rep->channel_count;
- for (int i = 0; i < rep->channel_count; i++)
- {
+
+ for (int i = 0; i < rep->channel_count; i++) {
_input_rc.values[i] = rep->rc_channel[i];
}
@@ -490,13 +518,16 @@ PX4IO::rx_callback(const uint8_t *buffer, size_t bytes_received)
dump_one = false;
printf("IO: %s armed ", rep->armed ? "" : "not");
+
for (unsigned i = 0; i < rep->channel_count; i++)
printf("%d: %d ", i, rep->rc_channel[i]);
+
printf("\n");
}
out:
- unlock();
+// unlock();
+ return;
}
void
@@ -509,9 +540,10 @@ PX4IO::io_send()
/* set outputs */
for (unsigned i = 0; i < _max_actuators; i++)
- cmd.servo_command[i] = _outputs.output[i];
+ cmd.output_control[i] = _outputs.output[i];
/* publish as we send */
+ /* XXX needs to be based off post-mix values from the IO side */
orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &_outputs);
/* update relays */
@@ -522,6 +554,7 @@ PX4IO::io_send()
cmd.arm_ok = (_armed.armed && !_armed.lockdown);
ret = hx_stream_send(_io_stream, &cmd, sizeof(cmd));
+
if (ret)
debug("send error %d", ret);
}
@@ -535,11 +568,47 @@ PX4IO::config_send()
cfg.f2i_config_magic = F2I_CONFIG_MAGIC;
ret = hx_stream_send(_io_stream, &cfg, sizeof(cfg));
+
if (ret)
debug("config error %d", ret);
}
int
+PX4IO::mixer_send(const char *buf, unsigned buflen)
+{
+ uint8_t frame[HX_STREAM_MAX_FRAME];
+ px4io_mixdata *msg = (px4io_mixdata *)&frame[0];
+
+ msg->f2i_mixer_magic = F2I_MIXER_MAGIC;
+ msg->action = F2I_MIXER_ACTION_RESET;
+
+ do {
+ unsigned count = buflen;
+
+ if (count > F2I_MIXER_MAX_TEXT)
+ count = F2I_MIXER_MAX_TEXT;
+
+ if (count > 0) {
+ memcpy(&msg->text[0], buf, count);
+ buf += count;
+ buflen -= count;
+ }
+
+ int ret = hx_stream_send(_io_stream, msg, sizeof(px4io_mixdata) + count);
+
+ if (ret) {
+ log("mixer send error %d", ret);
+ return ret;
+ }
+
+ msg->action = F2I_MIXER_ACTION_APPEND;
+
+ } while (buflen > 0);
+
+ return 0;
+}
+
+int
PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
{
int ret = OK;
@@ -562,7 +631,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1):
- /* fake an update to the selected servo channel */
+ /* fake an update to the selected 'servo' channel */
if ((arg >= 900) && (arg <= 2100)) {
_outputs.output[cmd - PWM_SERVO_SET(0)] = arg;
_send_needed = true;
@@ -603,67 +672,28 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
break;
case MIXERIOCGETOUTPUTCOUNT:
- *(unsigned *)arg = _max_actuators;
+ *(unsigned *)arg = PX4IO_CONTROL_CHANNELS;
break;
case MIXERIOCRESET:
- if (_mixers != nullptr) {
- delete _mixers;
- _mixers = nullptr;
- }
-
+ ret = 0; /* load always resets */
break;
- case MIXERIOCADDSIMPLE: {
- mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
+ case MIXERIOCLOADBUF:
- /* build the new mixer from the supplied argument */
- SimpleMixer *mixer = new SimpleMixer(control_callback,
- (uintptr_t)&_controls, mixinfo);
+ /* set the buffer up for transfer */
+ _mix_buf = (const char *)arg;
+ _mix_buf_len = strnlen(_mix_buf, 1024);
- /* validate the new mixer */
- if (mixer->check()) {
- delete mixer;
- ret = -EINVAL;
+ /* drop the lock and wait for the thread to clear the transmit */
+ unlock();
- } else {
- /* if we don't have a group yet, allocate one */
- if (_mixers == nullptr)
- _mixers = new MixerGroup(control_callback,
- (uintptr_t)&_controls);
+ while (_mix_buf != nullptr)
+ usleep(1000);
- /* add the new mixer to the group */
- _mixers->add_mixer(mixer);
- }
+ lock();
- }
- break;
-
- case MIXERIOCADDMULTIROTOR:
- /* XXX not yet supported */
- ret = -ENOTTY;
- break;
-
- case MIXERIOCLOADFILE: {
- MixerGroup *newmixers;
- const char *path = (const char *)arg;
-
- /* allocate a new mixer group and load it from the file */
- newmixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
-
- if (newmixers->load_from_file(path) != 0) {
- delete newmixers;
- ret = -EINVAL;
- }
-
- /* swap the new mixers in for the old */
- if (_mixers != nullptr) {
- delete _mixers;
- }
-
- _mixers = newmixers;
-
- }
+ ret = 0;
break;
default:
@@ -705,6 +735,13 @@ test(void)
close(fd);
+ actuator_armed_s aa;
+
+ aa.armed = true;
+ aa.lockdown = false;
+
+ orb_advertise(ORB_ID(actuator_armed), &aa);
+
exit(0);
}
@@ -724,6 +761,7 @@ monitor(void)
if (fds[0].revents == POLLIN) {
int c;
read(0, &c, 1);
+
if (cancels-- == 0)
exit(0);
}
@@ -810,6 +848,7 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "test"))
test();
+
if (!strcmp(argv[1], "monitor"))
monitor();
diff --git a/apps/drivers/px4io/uploader.cpp b/apps/drivers/px4io/uploader.cpp
index 8b354ff60..6442e947c 100644
--- a/apps/drivers/px4io/uploader.cpp
+++ b/apps/drivers/px4io/uploader.cpp
@@ -190,6 +190,7 @@ PX4IO_Uploader::drain()
do {
ret = recv(c, 250);
+
if (ret == OK) {
//log("discard 0x%02x", c);
}