aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_main.cpp
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:13:11 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:13:11 +0200
commit302233a34f23a57b67d4ebb8ba3e553ad9d8c445 (patch)
tree9fa902073c358151e1ca27430e00919048006d76 /src/modules/mavlink/mavlink_main.cpp
parentdfd9601b571057e73668d9b39d584bc4eb9cc305 (diff)
parentf0e28a60ca216ec147b359eef5500f190f192c82 (diff)
downloadpx4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.tar.gz
px4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.tar.bz2
px4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.zip
Merge branch 'master' into mpc_local_pos
Diffstat (limited to 'src/modules/mavlink/mavlink_main.cpp')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp231
1 files changed, 220 insertions, 11 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 18df577fe..a9f5f4de7 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -81,6 +81,7 @@
#include "mavlink_messages.h"
#include "mavlink_receiver.h"
#include "mavlink_rate_limiter.h"
+#include "mavlink_commands.h"
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -166,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);
@@ -185,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);
@@ -203,14 +209,21 @@ 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),
_mission_pub(-1),
+ _verbose(false),
+ _forwarding_on(false),
+ _passing_on(false),
+ _uart_fd(-1),
_mavlink_param_queue_index(0),
_subscribe_to_stream(nullptr),
_subscribe_to_stream_rate(0.0f),
_flow_control_enabled(true),
+ _message_buffer({}),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
@@ -261,7 +274,6 @@ Mavlink::Mavlink() :
errx(1, "instance ID is out of range");
break;
}
-
}
Mavlink::~Mavlink()
@@ -394,6 +406,18 @@ Mavlink::instance_exists(const char *device_name, Mavlink *self)
return false;
}
+void
+Mavlink::forward_message(mavlink_message_t *msg, Mavlink *self)
+{
+
+ Mavlink *inst;
+ LL_FOREACH(_mavlink_instances, inst) {
+ if (inst != self) {
+ inst->pass_message(msg);
+ }
+ }
+}
+
int
Mavlink::get_uart_fd(unsigned index)
{
@@ -808,10 +832,10 @@ void Mavlink::publish_mission()
{
/* Initialize mission publication if necessary */
if (_mission_pub < 0) {
- _mission_pub = orb_advertise(ORB_ID(mission), &mission);
+ _mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission);
} else {
- orb_publish(ORB_ID(mission), _mission_pub, &mission);
+ orb_publish(ORB_ID(offboard_mission), _mission_pub, &mission);
}
}
@@ -1617,6 +1641,125 @@ Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate)
}
int
+Mavlink::message_buffer_init(int size)
+{
+ _message_buffer.size = size;
+ _message_buffer.write_ptr = 0;
+ _message_buffer.read_ptr = 0;
+ _message_buffer.data = (char*)malloc(_message_buffer.size);
+ return (_message_buffer.data == 0) ? ERROR : OK;
+}
+
+void
+Mavlink::message_buffer_destroy()
+{
+ _message_buffer.size = 0;
+ _message_buffer.write_ptr = 0;
+ _message_buffer.read_ptr = 0;
+ free(_message_buffer.data);
+}
+
+int
+Mavlink::message_buffer_count()
+{
+ int n = _message_buffer.write_ptr - _message_buffer.read_ptr;
+
+ if (n < 0) {
+ n += _message_buffer.size;
+ }
+
+ return n;
+}
+
+int
+Mavlink::message_buffer_is_empty()
+{
+ return _message_buffer.read_ptr == _message_buffer.write_ptr;
+}
+
+
+bool
+Mavlink::message_buffer_write(void *ptr, int size)
+{
+ // bytes available to write
+ int available = _message_buffer.read_ptr - _message_buffer.write_ptr - 1;
+
+ if (available < 0) {
+ available += _message_buffer.size;
+ }
+
+ if (size > available) {
+ // buffer overflow
+ return false;
+ }
+
+ char *c = (char *) ptr;
+ int n = _message_buffer.size - _message_buffer.write_ptr; // bytes to end of the buffer
+
+ if (n < size) {
+ // message goes over end of the buffer
+ memcpy(&(_message_buffer.data[_message_buffer.write_ptr]), c, n);
+ _message_buffer.write_ptr = 0;
+
+ } else {
+ n = 0;
+ }
+
+ // now: n = bytes already written
+ int p = size - n; // number of bytes to write
+ memcpy(&(_message_buffer.data[_message_buffer.write_ptr]), &(c[n]), p);
+ _message_buffer.write_ptr = (_message_buffer.write_ptr + p) % _message_buffer.size;
+ return true;
+}
+
+int
+Mavlink::message_buffer_get_ptr(void **ptr, bool *is_part)
+{
+ // bytes available to read
+ int available = _message_buffer.write_ptr - _message_buffer.read_ptr;
+
+ if (available == 0) {
+ return 0; // buffer is empty
+ }
+
+ int n = 0;
+
+ if (available > 0) {
+ // read pointer is before write pointer, all available bytes can be read
+ n = available;
+ *is_part = false;
+
+ } else {
+ // read pointer is after write pointer, read bytes from read_ptr to end of the buffer
+ n = _message_buffer.size - _message_buffer.read_ptr;
+ *is_part = _message_buffer.write_ptr > 0;
+ }
+
+ *ptr = &(_message_buffer.data[_message_buffer.read_ptr]);
+ return n;
+}
+
+void
+Mavlink::message_buffer_mark_read(int n)
+{
+ _message_buffer.read_ptr = (_message_buffer.read_ptr + n) % _message_buffer.size;
+}
+
+void
+Mavlink::pass_message(mavlink_message_t *msg)
+{
+ if (_passing_on) {
+ /* size is 8 bytes plus variable payload */
+ int size = MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len;
+ pthread_mutex_lock(&_message_buffer_mutex);
+ message_buffer_write(msg, size);
+ pthread_mutex_unlock(&_message_buffer_mutex);
+ }
+}
+
+
+
+int
Mavlink::task_main(int argc, char *argv[])
{
int ch;
@@ -1632,7 +1775,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:v")) != EOF) {
+ while ((ch = getopt(argc, argv, "b:r:d:m:fpvw")) != EOF) {
switch (ch) {
case 'b':
_baudrate = strtoul(optarg, NULL, 10);
@@ -1672,10 +1815,22 @@ Mavlink::task_main(int argc, char *argv[])
break;
+ case 'f':
+ _forwarding_on = true;
+ break;
+
+ case 'p':
+ _passing_on = true;
+ break;
+
case 'v':
_verbose = true;
break;
+ case 'w':
+ _wait_to_transmit = true;
+ break;
+
default:
err_flag = true;
break;
@@ -1740,6 +1895,17 @@ Mavlink::task_main(int argc, char *argv[])
/* initialize mavlink text message buffering */
mavlink_logbuffer_init(&_logbuffer, 5);
+ /* if we are passing on mavlink messages, we need to prepare a buffer for this instance */
+ if (_passing_on) {
+ /* initialize message buffer if multiplexing is on */
+ if (OK != message_buffer_init(500)) {
+ errx(1, "can't allocate message buffer, exiting");
+ }
+
+ /* initialize message buffer mutex */
+ pthread_mutex_init(&_message_buffer_mutex, NULL);
+ }
+
/* create the device node that's used for sending text log messages, etc. */
register_driver(MAVLINK_LOG_DEVICE, &fops, 0666, NULL);
@@ -1766,6 +1932,8 @@ Mavlink::task_main(int argc, char *argv[])
struct vehicle_status_s *status = (struct vehicle_status_s *) status_sub->get_data();
+ MavlinkCommandsStream commands_stream(this, _channel);
+
/* add default streams depending on mode and intervals depending on datarate */
float rate_mult = _datarate / 1000.0f;
@@ -1783,6 +1951,9 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult);
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult);
+ configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f * rate_mult);
+ configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f * rate_mult);
+ configure_stream("DISTANCE_SENSOR", 0.5f);
break;
case MAVLINK_MODE_CAMERA:
@@ -1826,6 +1997,9 @@ Mavlink::task_main(int argc, char *argv[])
set_hil_enabled(status->hil_state == HIL_STATE_ON);
}
+ /* update commands stream */
+ commands_stream.update(t);
+
/* check for requested subscriptions */
if (_subscribe_to_stream != nullptr) {
if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) {
@@ -1884,6 +2058,37 @@ Mavlink::task_main(int argc, char *argv[])
}
}
+ /* pass messages from other UARTs */
+ if (_passing_on) {
+
+ bool is_part;
+ void *read_ptr;
+
+ /* guard get ptr by mutex */
+ pthread_mutex_lock(&_message_buffer_mutex);
+ int available = message_buffer_get_ptr(&read_ptr, &is_part);
+ pthread_mutex_unlock(&_message_buffer_mutex);
+
+ if (available > 0) {
+ /* write first part of buffer */
+ _mavlink_resend_uart(_channel, (const mavlink_message_t*)read_ptr);
+ message_buffer_mark_read(available);
+
+ /* write second part of buffer if there is some */
+ if (is_part) {
+ /* guard get ptr by mutex */
+ pthread_mutex_lock(&_message_buffer_mutex);
+ available = message_buffer_get_ptr(&read_ptr, &is_part);
+ pthread_mutex_unlock(&_message_buffer_mutex);
+
+ _mavlink_resend_uart(_channel, (const mavlink_message_t*)read_ptr);
+ message_buffer_mark_read(available);
+ }
+ }
+ }
+
+
+
perf_end(_loop_perf);
}
@@ -1928,6 +2133,10 @@ Mavlink::task_main(int argc, char *argv[])
/* close mavlink logging device */
close(_mavlink_fd);
+ if (_passing_on) {
+ message_buffer_destroy();
+ pthread_mutex_destroy(&_message_buffer_mutex);
+ }
/* destroy log buffer */
mavlink_logbuffer_destroy(&_logbuffer);
@@ -2067,7 +2276,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] [-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[])