Browse Source

Finished adding a '-w' option.

sbg
Helen Oleynikova 11 years ago committed by Julian Oes
parent
commit
e09aed917d
  1. 37
      src/modules/mavlink/mavlink_main.cpp
  2. 12
      src/modules/mavlink/mavlink_main.h
  3. 4
      src/modules/mavlink/mavlink_receiver.cpp

37
src/modules/mavlink/mavlink_main.cpp

@ -167,12 +167,12 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length @@ -167,12 +167,12 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
int buf_free = 0;
if (instance->get_flow_control_enabled()
&& ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) {
&& ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) {
if (buf_free == 0) {
if (last_write_times[(unsigned)channel] != 0 &&
hrt_elapsed_time(&last_write_times[(unsigned)channel]) > 500 * 1000UL) {
hrt_elapsed_time(&last_write_times[(unsigned)channel]) > 500 * 1000UL) {
warnx("DISABLING HARDWARE FLOW CONTROL");
instance->enable_flow_control(false);
@ -186,12 +186,17 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length @@ -186,12 +186,17 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
}
}
ssize_t ret = write(uart, ch, desired);
if (ret != desired) {
// XXX do something here, but change to using FIONWRITE and OS buf size for detection
/* If the wait until transmit flag is on, only transmit after we've received messages.
Otherwise, transmit all the time. */
if (instance->should_transmit()) {
ssize_t ret = write(uart, ch, desired);
if (ret != desired) {
// XXX do something here, but change to using FIONWRITE and OS buf size for detection
}
}
}
static void usage(void);
@ -204,6 +209,8 @@ Mavlink::Mavlink() : @@ -204,6 +209,8 @@ Mavlink::Mavlink() :
_task_running(false),
_hil_enabled(false),
_is_usb_uart(false),
_wait_to_transmit(false),
_received_messages(false),
_main_loop_delay(1000),
_subscriptions(nullptr),
_streams(nullptr),
@ -1776,7 +1783,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1776,7 +1783,7 @@ Mavlink::task_main(int argc, char *argv[])
* set error flag instead */
bool err_flag = false;
while ((ch = getopt(argc, argv, "b:r:d:m:fpv")) != EOF) {
while ((ch = getopt(argc, argv, "b:r:d:m:fpvw")) != EOF) {
switch (ch) {
case 'b':
_baudrate = strtoul(optarg, NULL, 10);
@ -1828,6 +1835,10 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1828,6 +1835,10 @@ Mavlink::task_main(int argc, char *argv[])
_verbose = true;
break;
case 'w':
_wait_to_transmit = true;
break;
default:
err_flag = true;
break;
@ -2172,11 +2183,11 @@ Mavlink::start(int argc, char *argv[]) @@ -2172,11 +2183,11 @@ Mavlink::start(int argc, char *argv[])
// task - start_helper() only returns
// when the started task exits.
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
(main_t)&Mavlink::start_helper,
(const char **)argv);
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
(main_t)&Mavlink::start_helper,
(const char **)argv);
// Ensure that this shell command
// does not return before the instance
@ -2272,7 +2283,7 @@ Mavlink::stream(int argc, char *argv[]) @@ -2272,7 +2283,7 @@ Mavlink::stream(int argc, char *argv[])
static void usage()
{
warnx("usage: mavlink {start|stop-all|stream} [-d device] [-b baudrate] [-r rate] [-m mode] [-s stream] [-f] [-p] [-v]");
warnx("usage: mavlink {start|stop-all|stream} [-d device] [-b baudrate] [-r rate] [-m mode] [-s stream] [-f] [-p] [-v] [-w]");
}
int mavlink_main(int argc, char *argv[])

12
src/modules/mavlink/mavlink_main.h

@ -202,6 +202,14 @@ public: @@ -202,6 +202,14 @@ public:
int get_mavlink_fd() { return _mavlink_fd; }
/* Functions for waiting to start transmission until message received. */
void set_has_received_messages(bool received_messages) { _received_messages = received_messages; }
bool get_has_received_messages() { return _received_messages; }
void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
bool get_wait_to_transmit() { return _wait_to_transmit; }
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
protected:
Mavlink *next;
@ -216,6 +224,8 @@ private: @@ -216,6 +224,8 @@ private:
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
bool _is_usb_uart; /**< Port is USB */
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
bool _received_messages; /**< Whether we've received valid mavlink messages. */
unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
@ -270,6 +280,8 @@ private: @@ -270,6 +280,8 @@ private:
pthread_mutex_t _message_buffer_mutex;
/**
* Send one parameter.
*

4
src/modules/mavlink/mavlink_receiver.cpp

@ -179,6 +179,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) @@ -179,6 +179,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
break;
}
}
/* If we've received a valid message, mark the flag indicating so.
This is used in the '-w' command-line flag. */
_mavlink->set_has_received_messages(true);
}
void

Loading…
Cancel
Save