aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:18:07 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:18:07 +0200
commite4a4430f9f0be24c661e507f6e959a571937934c (patch)
tree4c857608a2be975ac493c04a4c0af6571b7de619 /src
parent0b97dd2b776ce61fd53776f036230ea0089e26e9 (diff)
parentaefea1a95d221e541be219d9fec7eece3c72fd50 (diff)
downloadpx4-firmware-e4a4430f9f0be24c661e507f6e959a571937934c.tar.gz
px4-firmware-e4a4430f9f0be24c661e507f6e959a571937934c.tar.bz2
px4-firmware-e4a4430f9f0be24c661e507f6e959a571937934c.zip
Merge branch 'master' into rc_timeout
Diffstat (limited to 'src')
-rw-r--r--src/drivers/blinkm/blinkm.cpp141
-rw-r--r--src/drivers/drv_range_finder.h11
-rw-r--r--src/drivers/gps/gps.cpp4
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp9
-rw-r--r--src/modules/commander/commander.cpp11
-rw-r--r--src/modules/dataman/dataman.c19
-rw-r--r--src/modules/dataman/dataman.h2
-rw-r--r--src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp2
-rw-r--r--src/modules/mavlink/mavlink_commands.cpp73
-rw-r--r--src/modules/mavlink/mavlink_commands.h65
-rw-r--r--src/modules/mavlink/mavlink_main.cpp236
-rw-r--r--src/modules/mavlink/mavlink_main.h48
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp126
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp9
-rw-r--r--src/modules/mavlink/mavlink_stream.h2
-rw-r--r--src/modules/mavlink/module.mk5
-rw-r--r--src/modules/navigator/navigator_main.cpp6
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c2
-rw-r--r--src/modules/sdlog2/sdlog2.c48
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h61
-rw-r--r--src/modules/uORB/objects_common.cpp2
-rw-r--r--src/modules/uORB/topics/mission.h2
23 files changed, 737 insertions, 149 deletions
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 2361f4dd1..b75c2297f 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -48,11 +48,14 @@
* The recognized number off cells, will be blinked 5 times in purple color.
* 2 Cells = 2 blinks
* ...
- * 5 Cells = 5 blinks
+ * 6 Cells = 6 blinks
* Now the Application will show the actual selected Flightmode, GPS-Fix and Battery Warnings and Alerts.
*
- * System disarmed:
- * The BlinkM should lit solid red.
+ * System disarmed and safe:
+ * The BlinkM should light solid cyan.
+ *
+ * System safety off but not armed:
+ * The BlinkM should light flashing orange
*
* System armed:
* One message is made of 4 Blinks and a pause in the same length as the 4 blinks.
@@ -67,10 +70,10 @@
* (X = on, _=off)
*
* The first 3 blinks indicates the status of the GPS-Signal (red):
- * 0-4 satellites = X-X-X-X-_-_-_-_-_-_-
- * 5 satellites = X-X-_-X-_-_-_-_-_-_-
- * 6 satellites = X-_-_-X-_-_-_-_-_-_-
- * >=7 satellites = _-_-_-X-_-_-_-_-_-_-
+ * 0-4 satellites = X-X-X-X-X-_-_-_-_-_-
+ * 5 satellites = X-X-_-X-X-_-_-_-_-_-
+ * 6 satellites = X-_-_-X-X-_-_-_-_-_-
+ * >=7 satellites = _-_-_-X-X-_-_-_-_-_-
* If no GPS is found the first 3 blinks are white
*
* The fourth Blink indicates the Flightmode:
@@ -119,6 +122,7 @@
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/safety.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
static const int LED_ONTIME = 120;
@@ -166,10 +170,12 @@ private:
enum ledColors {
LED_OFF,
LED_RED,
+ LED_ORANGE,
LED_YELLOW,
LED_PURPLE,
LED_GREEN,
LED_BLUE,
+ LED_CYAN,
LED_WHITE,
LED_AMBER
};
@@ -380,6 +386,7 @@ BlinkM::led()
static int vehicle_control_mode_sub_fd;
static int vehicle_gps_position_sub_fd;
static int actuator_armed_sub_fd;
+ static int safety_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -402,16 +409,20 @@ BlinkM::led()
if(!topic_initialized) {
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
- orb_set_interval(vehicle_status_sub_fd, 1000);
+ orb_set_interval(vehicle_status_sub_fd, 250);
vehicle_control_mode_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
- orb_set_interval(vehicle_control_mode_sub_fd, 1000);
+ orb_set_interval(vehicle_control_mode_sub_fd, 250);
actuator_armed_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(actuator_armed_sub_fd, 1000);
+ orb_set_interval(actuator_armed_sub_fd, 250);
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
- orb_set_interval(vehicle_gps_position_sub_fd, 1000);
+ orb_set_interval(vehicle_gps_position_sub_fd, 250);
+
+ /* Subscribe to safety topic */
+ safety_sub_fd = orb_subscribe(ORB_ID(safety));
+ orb_set_interval(safety_sub_fd, 250);
topic_initialized = true;
}
@@ -433,7 +444,9 @@ BlinkM::led()
if(num_of_cells > 4) {
t_led_color[4] = LED_PURPLE;
}
- t_led_color[5] = LED_OFF;
+ if(num_of_cells > 5) {
+ t_led_color[5] = LED_PURPLE;
+ }
t_led_color[6] = LED_OFF;
t_led_color[7] = LED_OFF;
t_led_blink = LED_BLINK;
@@ -467,14 +480,17 @@ BlinkM::led()
struct vehicle_control_mode_s vehicle_control_mode;
struct actuator_armed_s actuator_armed;
struct vehicle_gps_position_s vehicle_gps_position_raw;
+ struct safety_s safety;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
+ memset(&safety, 0, sizeof(safety));
bool new_data_vehicle_status;
bool new_data_vehicle_control_mode;
bool new_data_actuator_armed;
bool new_data_vehicle_gps_position;
+ bool new_data_safety;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -520,7 +536,12 @@ BlinkM::led()
no_data_vehicle_gps_position = 3;
}
+ /* update safety topic */
+ orb_check(safety_sub_fd, &new_data_safety);
+ if (new_data_safety) {
+ orb_copy(ORB_ID(safety), safety_sub_fd, &safety);
+ }
/* get number of used satellites in navigation */
num_of_used_sats = 0;
@@ -541,19 +562,7 @@ BlinkM::led()
printf("<blinkm> cells found:%d\n", num_of_cells);
} else {
- if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
- /* LED Pattern for battery low warning */
- led_color_1 = LED_YELLOW;
- led_color_2 = LED_YELLOW;
- led_color_3 = LED_YELLOW;
- led_color_4 = LED_YELLOW;
- led_color_5 = LED_YELLOW;
- led_color_6 = LED_YELLOW;
- led_color_7 = LED_YELLOW;
- led_color_8 = LED_YELLOW;
- led_blink = LED_BLINK;
-
- } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
+ if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
/* LED Pattern for battery critical alerting */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -565,21 +574,56 @@ BlinkM::led()
led_color_8 = LED_RED;
led_blink = LED_BLINK;
+ } else if(vehicle_status_raw.rc_signal_lost) {
+ /* LED Pattern for FAILSAFE */
+ led_color_1 = LED_BLUE;
+ led_color_2 = LED_BLUE;
+ led_color_3 = LED_BLUE;
+ led_color_4 = LED_BLUE;
+ led_color_5 = LED_BLUE;
+ led_color_6 = LED_BLUE;
+ led_color_7 = LED_BLUE;
+ led_color_8 = LED_BLUE;
+ led_blink = LED_BLINK;
+
+ } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
+ /* LED Pattern for battery low warning */
+ led_color_1 = LED_YELLOW;
+ led_color_2 = LED_YELLOW;
+ led_color_3 = LED_YELLOW;
+ led_color_4 = LED_YELLOW;
+ led_color_5 = LED_YELLOW;
+ led_color_6 = LED_YELLOW;
+ led_color_7 = LED_YELLOW;
+ led_color_8 = LED_YELLOW;
+ led_blink = LED_BLINK;
+
} else {
/* no battery warnings here */
if(actuator_armed.armed == false) {
/* system not armed */
- led_color_1 = LED_RED;
- led_color_2 = LED_RED;
- led_color_3 = LED_RED;
- led_color_4 = LED_RED;
- led_color_5 = LED_RED;
- led_color_6 = LED_RED;
- led_color_7 = LED_RED;
- led_color_8 = LED_RED;
- led_blink = LED_NOBLINK;
-
+ if(safety.safety_off){
+ led_color_1 = LED_ORANGE;
+ led_color_2 = LED_ORANGE;
+ led_color_3 = LED_ORANGE;
+ led_color_4 = LED_ORANGE;
+ led_color_5 = LED_ORANGE;
+ led_color_6 = LED_ORANGE;
+ led_color_7 = LED_ORANGE;
+ led_color_8 = LED_ORANGE;
+ led_blink = LED_BLINK;
+ }else{
+ led_color_1 = LED_CYAN;
+ led_color_2 = LED_CYAN;
+ led_color_3 = LED_CYAN;
+ led_color_4 = LED_CYAN;
+ led_color_5 = LED_CYAN;
+ led_color_6 = LED_CYAN;
+ led_color_7 = LED_CYAN;
+ led_color_8 = LED_CYAN;
+ led_blink = LED_NOBLINK;
+ }
} else {
/* armed system - initial led pattern */
led_color_1 = LED_RED;
@@ -593,23 +637,22 @@ BlinkM::led()
led_blink = LED_BLINK;
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
-
- //XXX please check
- if (vehicle_control_mode.flag_control_position_enabled)
+ /* indicate main control state */
+ if (vehicle_status_raw.main_state == MAIN_STATE_EASY)
led_color_4 = LED_GREEN;
- else if (vehicle_control_mode.flag_control_velocity_enabled)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
led_color_4 = LED_BLUE;
- else if (vehicle_control_mode.flag_control_attitude_enabled)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_SEATBELT)
led_color_4 = LED_YELLOW;
- else if (vehicle_control_mode.flag_control_manual_enabled)
- led_color_4 = LED_AMBER;
+ else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
+ led_color_4 = LED_WHITE;
else
led_color_4 = LED_OFF;
-
+ led_color_5 = led_color_4;
}
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat�s */
+ /* handling used satus */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
@@ -690,8 +733,11 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_RED: // red
set_rgb(255,0,0);
break;
+ case LED_ORANGE: // orange
+ set_rgb(255,150,0);
+ break;
case LED_YELLOW: // yellow
- set_rgb(255,70,0);
+ set_rgb(200,200,0);
break;
case LED_PURPLE: // purple
set_rgb(255,0,255);
@@ -702,11 +748,14 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_BLUE: // blue
set_rgb(0,0,255);
break;
+ case LED_CYAN: // cyan
+ set_rgb(0,128,128);
+ break;
case LED_WHITE: // white
set_rgb(255,255,255);
break;
case LED_AMBER: // amber
- set_rgb(255,20,0);
+ set_rgb(255,65,0);
break;
}
}
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index cf91f7030..e45939b37 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -46,6 +46,10 @@
#define RANGE_FINDER_DEVICE_PATH "/dev/range_finder"
+enum RANGE_FINDER_TYPE {
+ RANGE_FINDER_TYPE_LASER = 0,
+};
+
/**
* range finder report structure. Reads from the device must be in multiples of this
* structure.
@@ -53,8 +57,11 @@
struct range_finder_report {
uint64_t timestamp;
uint64_t error_count;
- float distance; /** in meters */
- uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
+ unsigned type; /**< type, following RANGE_FINDER_TYPE enum */
+ float distance; /**< in meters */
+ float minimum_distance; /**< minimum distance the sensor can measure */
+ float maximum_distance; /**< maximum distance the sensor can measure */
+ uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */
};
/*
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index c72f692d7..a902bdf2f 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -282,8 +282,8 @@ GPS::task_main()
_report.p_variance_m = 10.0f;
_report.c_variance_rad = 0.1f;
_report.fix_type = 3;
- _report.eph_m = 10.0f;
- _report.epv_m = 10.0f;
+ _report.eph_m = 3.0f;
+ _report.epv_m = 7.0f;
_report.timestamp_velocity = hrt_absolute_time();
_report.vel_n_m_s = 0.0f;
_report.vel_e_m_s = 0.0f;
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index dd8abbac5..28ec62356 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -201,9 +201,14 @@ PX4IO_Uploader::upload(const char *filenames[])
continue;
}
- if (bl_rev <= 2)
+ if (bl_rev <= 2) {
ret = verify_rev2(fw_size);
- else if(bl_rev == 3) {
+ } else if(bl_rev == 3) {
+ ret = verify_rev3(fw_size);
+ } else {
+ /* verify rev 4 and higher still uses the same approach and
+ * every version *needs* to be verified.
+ */
ret = verify_rev3(fw_size);
}
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index d4567c4f1..271209412 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -395,6 +395,11 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
enum VEHICLE_CMD_RESULT result = VEHICLE_CMD_RESULT_UNSUPPORTED;
bool ret = false;
+ /* only handle commands that are meant to be handled by this system and component */
+ if (cmd->target_system != status->system_id || ((cmd->target_component != status->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components
+ return false;
+ }
+
/* only handle high-priority commands here */
/* request to set different system mode */
@@ -587,11 +592,11 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
break;
default:
- /* warn about unsupported commands */
+ /* Warn about unsupported commands, this makes sense because only commands
+ * to this component ID (or all) are passed by mavlink. */
answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
-
if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(*cmd, result);
@@ -967,7 +972,7 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(battery_status), battery_sub, &battery);
/* only consider battery voltage if system has been running 2s and battery voltage is valid */
- if (status.hil_state == HIL_STATE_OFF && hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
+ if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
status.battery_voltage = battery.voltage_filtered_v;
status.battery_current = battery.current_a;
status.condition_battery_voltage_valid = true;
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 34d20e485..c132b0040 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -44,7 +44,9 @@
#include <stdlib.h>
#include <fcntl.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
#include <queue.h>
+#include <string.h>
#include "dataman.h"
@@ -594,6 +596,20 @@ task_main(int argc, char *argv[])
sem_init(&g_work_queued_sema, 1, 0);
+ /* See if the data manage file exists and is a multiple of the sector size */
+ g_task_fd = open(k_data_manager_device_path, O_RDONLY | O_BINARY);
+ if (g_task_fd >= 0) {
+ /* File exists, check its size */
+ int file_size = lseek(g_task_fd, 0, SEEK_END);
+ if ((file_size % k_sector_size) != 0) {
+ warnx("Incompatible data manager file %s, resetting it", k_data_manager_device_path);
+ close(g_task_fd);
+ unlink(k_data_manager_device_path);
+ }
+ else
+ close(g_task_fd);
+ }
+
/* Open or create the data manager file */
g_task_fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY);
@@ -603,7 +619,7 @@ task_main(int argc, char *argv[])
return -1;
}
- if (lseek(g_task_fd, max_offset, SEEK_SET) != max_offset) {
+ if ((unsigned)lseek(g_task_fd, max_offset, SEEK_SET) != max_offset) {
close(g_task_fd);
warnx("Could not seek data manager file %s", k_data_manager_device_path);
sem_post(&g_init_sema); /* Don't want to hang startup */
@@ -776,4 +792,3 @@ dataman_main(int argc, char *argv[])
exit(1);
}
-
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index a70638ccc..33c9fcd15 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -79,7 +79,7 @@ extern "C" {
} dm_reset_reason;
/* Maximum size in bytes of a single item instance */
- #define DM_MAX_DATA_SIZE 126
+ #define DM_MAX_DATA_SIZE 124
/* Retrieve from the data manager store */
__EXPORT ssize_t
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
index 840cd585e..8ea611802 100644
--- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
+++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
@@ -959,7 +959,7 @@ FixedwingEstimator::task_main()
}
// Publish results
- if (_initialized) {
+ if (_initialized && (check == OK)) {
diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp
new file mode 100644
index 000000000..1c1e097a4
--- /dev/null
+++ b/src/modules/mavlink/mavlink_commands.cpp
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mavlink_commands.cpp
+ * Mavlink commands stream implementation.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include "mavlink_commands.h"
+
+MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel)
+{
+ _cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
+ _cmd = (struct vehicle_command_s *)_cmd_sub->get_data();
+}
+
+MavlinkCommandsStream::~MavlinkCommandsStream()
+{
+}
+
+void
+MavlinkCommandsStream::update(const hrt_abstime t)
+{
+ if (_cmd_sub->update(t)) {
+ /* only send commands for other systems/components */
+ if (_cmd->target_system != mavlink_system.sysid || _cmd->target_component != mavlink_system.compid) {
+ mavlink_msg_command_long_send(_channel,
+ _cmd->target_system,
+ _cmd->target_component,
+ _cmd->command,
+ _cmd->confirmation,
+ _cmd->param1,
+ _cmd->param2,
+ _cmd->param3,
+ _cmd->param4,
+ _cmd->param5,
+ _cmd->param6,
+ _cmd->param7);
+ }
+ }
+}
diff --git a/src/modules/mavlink/mavlink_commands.h b/src/modules/mavlink/mavlink_commands.h
new file mode 100644
index 000000000..6255d65df
--- /dev/null
+++ b/src/modules/mavlink/mavlink_commands.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mavlink_commands.h
+ * Mavlink commands stream definition.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef MAVLINK_COMMANDS_H_
+#define MAVLINK_COMMANDS_H_
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_command.h>
+
+class Mavlink;
+class MavlinkCommansStream;
+
+#include "mavlink_main.h"
+
+class MavlinkCommandsStream
+{
+private:
+ MavlinkOrbSubscription *_cmd_sub;
+ struct vehicle_command_s *_cmd;
+ mavlink_channel_t _channel;
+
+public:
+ MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel);
+ ~MavlinkCommandsStream();
+ void update(const hrt_abstime t);
+};
+
+#endif /* MAVLINK_COMMANDS_H_ */
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 18df577fe..227e99b48 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)
{
@@ -550,6 +574,11 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
/* open uart */
_uart_fd = open(uart_name, O_RDWR | O_NOCTTY);
+ if (_uart_fd < 0) {
+ return _uart_fd;
+ }
+
+
/* Try to set baud rate */
struct termios uart_config;
int termios_state;
@@ -808,10 +837,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 +1646,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 +1780,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 +1820,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 +1900,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 +1937,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 +1956,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 +2002,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 +2063,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 +2138,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 +2281,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[])
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 5a118a0ad..66d82b471 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -138,6 +138,8 @@ public:
static bool instance_exists(const char *device_name, Mavlink *self);
+ static void forward_message(mavlink_message_t *msg, Mavlink *self);
+
static int get_uart_fd(unsigned index);
int get_uart_fd();
@@ -153,10 +155,12 @@ public:
void set_mode(enum MAVLINK_MODE);
enum MAVLINK_MODE get_mode() { return _mode; }
- bool get_hil_enabled() { return _hil_enabled; };
+ bool get_hil_enabled() { return _hil_enabled; }
bool get_flow_control_enabled() { return _flow_control_enabled; }
+ bool get_forwarding_on() { return _forwarding_on; }
+
/**
* Handle waypoint related messages.
*/
@@ -196,6 +200,16 @@ public:
bool _task_should_exit; /**< if true, mavlink task should exit */
+ 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;
@@ -210,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 */
@@ -234,6 +250,8 @@ private:
mavlink_wpm_storage *_wpm;
bool _verbose;
+ bool _forwarding_on;
+ bool _passing_on;
int _uart_fd;
int _baudrate;
int _datarate;
@@ -252,6 +270,18 @@ private:
bool _flow_control_enabled;
+ struct mavlink_message_buffer {
+ int write_ptr;
+ int read_ptr;
+ int size;
+ char *data;
+ };
+ mavlink_message_buffer _message_buffer;
+
+ pthread_mutex_t _message_buffer_mutex;
+
+
+
/**
* Send one parameter.
*
@@ -315,6 +345,22 @@ private:
int configure_stream(const char *stream_name, const float rate);
void configure_stream_threadsafe(const char *stream_name, const float rate);
+ int message_buffer_init(int size);
+
+ void message_buffer_destroy();
+
+ int message_buffer_count();
+
+ int message_buffer_is_empty();
+
+ bool message_buffer_write(void *ptr, int size);
+
+ int message_buffer_get_ptr(void **ptr, bool *is_part);
+
+ void message_buffer_mark_read(int n);
+
+ void pass_message(mavlink_message_t *msg);
+
static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg);
/**
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 4ca3840d4..678ce1645 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -72,6 +72,7 @@
#include <uORB/topics/navigation_capabilities.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
+#include <drivers/drv_range_finder.h>
#include "mavlink_messages.h"
@@ -262,22 +263,21 @@ protected:
void send(const hrt_abstime t)
{
- if (status_sub->update(t)) {
- mavlink_msg_sys_status_send(_channel,
- status->onboard_control_sensors_present,
- status->onboard_control_sensors_enabled,
- status->onboard_control_sensors_health,
- status->load * 1000.0f,
- status->battery_voltage * 1000.0f,
- status->battery_current * 1000.0f,
- status->battery_remaining,
- status->drop_rate_comm,
- status->errors_comm,
- status->errors_count1,
- status->errors_count2,
- status->errors_count3,
- status->errors_count4);
- }
+ status_sub->update(t);
+ mavlink_msg_sys_status_send(_channel,
+ status->onboard_control_sensors_present,
+ status->onboard_control_sensors_enabled,
+ status->onboard_control_sensors_health,
+ status->load * 1000.0f,
+ status->battery_voltage * 1000.0f,
+ status->battery_current * 1000.0f,
+ status->battery_remaining * 100.0f,
+ status->drop_rate_comm,
+ status->errors_comm,
+ status->errors_count1,
+ status->errors_count2,
+ status->errors_count3,
+ status->errors_count4);
}
};
@@ -641,6 +641,47 @@ protected:
};
+
+class MavlinkStreamViconPositionEstimate : public MavlinkStream
+{
+public:
+ const char *get_name()
+ {
+ return "VICON_POSITION_ESTIMATE";
+ }
+
+ MavlinkStream *new_instance()
+ {
+ return new MavlinkStreamViconPositionEstimate();
+ }
+
+private:
+ MavlinkOrbSubscription *pos_sub;
+ struct vehicle_vicon_position_s *pos;
+
+protected:
+ void subscribe(Mavlink *mavlink)
+ {
+ pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position));
+ pos = (struct vehicle_vicon_position_s *)pos_sub->get_data();
+ }
+
+ void send(const hrt_abstime t)
+ {
+ if (pos_sub->update(t)) {
+ mavlink_msg_vicon_position_estimate_send(_channel,
+ pos->timestamp / 1000,
+ pos->x,
+ pos->y,
+ pos->z,
+ pos->roll,
+ pos->pitch,
+ pos->yaw);
+ }
+ }
+};
+
+
class MavlinkStreamGPSGlobalOrigin : public MavlinkStream
{
public:
@@ -1253,8 +1294,6 @@ protected:
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
status = (struct vehicle_status_s *)status_sub->get_data();
-
-
}
void send(const hrt_abstime t)
@@ -1265,12 +1304,57 @@ protected:
|| status->arming_state == ARMING_STATE_ARMED_ERROR) {
/* send camera capture on */
- mavlink_msg_command_long_send(_channel, 42, 30, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
+ mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
} else {
/* send camera capture off */
- mavlink_msg_command_long_send(_channel, 42, 30, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
+ mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
+ }
+ }
+};
+
+class MavlinkStreamDistanceSensor : public MavlinkStream
+{
+public:
+ const char *get_name()
+ {
+ return "DISTANCE_SENSOR";
+ }
+
+ MavlinkStream *new_instance()
+ {
+ return new MavlinkStreamDistanceSensor();
+ }
+
+private:
+ MavlinkOrbSubscription *range_sub;
+ struct range_finder_report *range;
+
+protected:
+ void subscribe(Mavlink *mavlink)
+ {
+ range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder));
+ range = (struct range_finder_report *)range_sub->get_data();
+ }
+
+ void send(const hrt_abstime t)
+ {
+ (void)range_sub->update(t);
+
+ uint8_t type;
+
+ switch (range->type) {
+ case RANGE_FINDER_TYPE_LASER:
+ type = MAV_DISTANCE_SENSOR_LASER;
+ break;
}
+
+ uint8_t id = 0;
+ uint8_t orientation = 0;
+ uint8_t covariance = 20;
+
+ mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
+ range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
}
};
@@ -1300,5 +1384,7 @@ MavlinkStream *streams_list[] = {
new MavlinkStreamAttitudeControls(),
new MavlinkStreamNamedValueFloat(),
new MavlinkStreamCameraCapture(),
+ new MavlinkStreamDistanceSensor(),
+ new MavlinkStreamViconPositionEstimate(),
nullptr
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index f6f5e4848..f5029652d 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -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
@@ -880,6 +884,11 @@ MavlinkReceiver::receive_thread(void *arg)
/* handle packet with parameter component */
_mavlink->mavlink_pm_message_handler(_mavlink->get_channel(), &msg);
+
+ if (_mavlink->get_forwarding_on()) {
+ /* forward any messages to other mavlink instances */
+ Mavlink::forward_message(&msg, _mavlink);
+ }
}
}
}
diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h
index 135e1bce0..def40d9ad 100644
--- a/src/modules/mavlink/mavlink_stream.h
+++ b/src/modules/mavlink/mavlink_stream.h
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file mavlink_stream.cpp
+ * @file mavlink_stream.h
* Mavlink messages stream definition.
*
* @author Anton Babushkin <anton.babushkin@me.com>
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index f09efa2e6..dcca11977 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -42,6 +42,9 @@ SRCS += mavlink_main.cpp \
mavlink_orb_subscription.cpp \
mavlink_messages.cpp \
mavlink_stream.cpp \
- mavlink_rate_limiter.cpp
+ mavlink_rate_limiter.cpp \
+ mavlink_commands.cpp
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 1bb5d33a1..494266dd3 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -510,7 +510,7 @@ Navigator::offboard_mission_update(bool isrotaryWing)
{
struct mission_s offboard_mission;
- if (orb_copy(ORB_ID(mission), _offboard_mission_sub, &offboard_mission) == OK) {
+ if (orb_copy(ORB_ID(offboard_mission), _offboard_mission_sub, &offboard_mission) == OK) {
/* Check mission feasibility, for now do not handle the return value,
* however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
@@ -543,7 +543,7 @@ Navigator::onboard_mission_update()
{
struct mission_s onboard_mission;
- if (orb_copy(ORB_ID(mission), _onboard_mission_sub, &onboard_mission) == OK) {
+ if (orb_copy(ORB_ID(onboard_mission), _onboard_mission_sub, &onboard_mission) == OK) {
_mission.set_onboard_mission_count(onboard_mission.count);
_mission.set_current_onboard_mission_index(onboard_mission.current_index);
@@ -611,7 +611,7 @@ Navigator::task_main()
* do subscriptions
*/
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- _offboard_mission_sub = orb_subscribe(ORB_ID(mission));
+ _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
_onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 368fa6ee2..763b87563 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -763,7 +763,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float thrust = armed.armed ? actuator.control[3] : 0.0f;
if (landed) {
- if (alt_disp2 > land_disp2 && thrust > params.land_thr) {
+ if (alt_disp2 > land_disp2 || thrust > params.land_thr) {
landed = false;
landed_time = 0;
}
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index b71f9472f..dcad5c03b 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -56,7 +56,7 @@ PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.05f);
PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
-PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.3f);
+PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f);
int parameters_init(struct position_estimator_inav_param_handles *h)
{
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 4b2d01c71..543f15093 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -226,11 +226,11 @@ sdlog2_usage(const char *reason)
}
errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
- "\t-r\tLog rate in Hz, 0 means unlimited rate\n"
- "\t-b\tLog buffer size in KiB, default is 8\n"
- "\t-e\tEnable logging by default (if not, can be started by command)\n"
- "\t-a\tLog only when armed (can be still overriden by command)\n"
- "\t-t\tUse date/time for naming log directories and files\n");
+ "\t-r\tLog rate in Hz, 0 means unlimited rate\n"
+ "\t-b\tLog buffer size in KiB, default is 8\n"
+ "\t-e\tEnable logging by default (if not, can be started by command)\n"
+ "\t-a\tLog only when armed (can be still overriden by command)\n"
+ "\t-t\tUse date/time for naming log directories and files\n");
}
/**
@@ -257,11 +257,11 @@ int sdlog2_main(int argc, char *argv[])
main_thread_should_exit = false;
deamon_task = task_spawn_cmd("sdlog2",
- SCHED_DEFAULT,
- SCHED_PRIORITY_DEFAULT - 30,
- 3000,
- sdlog2_thread_main,
- (const char **)argv);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT - 30,
+ 3000,
+ sdlog2_thread_main,
+ (const char **)argv);
exit(0);
}
@@ -833,6 +833,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_TELE_s log_TELE;
struct log_ESTM_s log_ESTM;
struct log_PWR_s log_PWR;
+ struct log_VICN_s log_VICN;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -907,9 +908,6 @@ int sdlog2_thread_main(int argc, char *argv[])
hrt_abstime barometer_timestamp = 0;
hrt_abstime differential_pressure_timestamp = 0;
- /* track changes in distance status */
- bool dist_bottom_present = false;
-
/* enable logging on start if needed */
if (log_on_start) {
/* check GPS topic to get GPS time */
@@ -1098,6 +1096,8 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_LPOS.x = buf.local_pos.x;
log_msg.body.log_LPOS.y = buf.local_pos.y;
log_msg.body.log_LPOS.z = buf.local_pos.z;
+ log_msg.body.log_LPOS.ground_dist = buf.local_pos.dist_bottom;
+ log_msg.body.log_LPOS.ground_dist_rate = buf.local_pos.dist_bottom_rate;
log_msg.body.log_LPOS.vx = buf.local_pos.vx;
log_msg.body.log_LPOS.vy = buf.local_pos.vy;
log_msg.body.log_LPOS.vz = buf.local_pos.vz;
@@ -1107,19 +1107,8 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
log_msg.body.log_LPOS.landed = buf.local_pos.landed;
+ log_msg.body.log_LPOS.ground_dist_flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
LOGBUFFER_WRITE_AND_COUNT(LPOS);
-
- if (buf.local_pos.dist_bottom_valid) {
- dist_bottom_present = true;
- }
-
- if (dist_bottom_present) {
- log_msg.msg_type = LOG_DIST_MSG;
- log_msg.body.log_DIST.bottom = buf.local_pos.dist_bottom;
- log_msg.body.log_DIST.bottom_rate = buf.local_pos.dist_bottom_rate;
- log_msg.body.log_DIST.flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
- LOGBUFFER_WRITE_AND_COUNT(DIST);
- }
}
/* --- LOCAL POSITION SETPOINT --- */
@@ -1163,7 +1152,14 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- VICON POSITION --- */
if (copy_if_updated(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos)) {
- // TODO not implemented yet
+ log_msg.msg_type = LOG_VICN_MSG;
+ log_msg.body.log_VICN.x = buf.vicon_pos.x;
+ log_msg.body.log_VICN.y = buf.vicon_pos.y;
+ log_msg.body.log_VICN.z = buf.vicon_pos.z;
+ log_msg.body.log_VICN.pitch = buf.vicon_pos.pitch;
+ log_msg.body.log_VICN.roll = buf.vicon_pos.roll;
+ log_msg.body.log_VICN.yaw = buf.vicon_pos.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(VICN);
}
/* --- FLOW --- */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 4b70e55c9..4aca1dcd0 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -101,6 +101,8 @@ struct log_LPOS_s {
float x;
float y;
float z;
+ float ground_dist;
+ float ground_dist_rate;
float vx;
float vy;
float vz;
@@ -110,6 +112,7 @@ struct log_LPOS_s {
uint8_t xy_flags;
uint8_t z_flags;
uint8_t landed;
+ uint8_t ground_dist_flags;
};
/* --- LPSP - LOCAL POSITION SETPOINT --- */
@@ -302,6 +305,17 @@ struct log_PWR_s {
uint8_t high_power_rail_overcurrent;
};
+/* --- VICN - VICON POSITION --- */
+#define LOG_VICN_MSG 25
+struct log_VICN_s {
+ float x;
+ float y;
+ float z;
+ float roll;
+ float pitch;
+ float yaw;
+};
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -329,29 +343,30 @@ struct log_PARM_s {
/* construct list of all message formats */
static const struct log_format_s log_formats[] = {
/* business-level messages, ID < 0x80 */
- LOG_FORMAT(ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
- LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
- LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
- LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
- LOG_FORMAT(LPOS, "ffffffLLfBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,XYFlags,ZFlags,Landed"),
- LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
- LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
- LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
- LOG_FORMAT(STAT, "BBfBB", "MainState,ArmState,BatRem,BatWarn,Landed"),
- LOG_FORMAT(RC, "ffffffffBB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count,SignalLost"),
- LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
- LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
- LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
- LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
- LOG_FORMAT(GPOS, "LLfffffB", "Lat,Lon,Alt,VelN,VelE,VelD,BaroAlt,Flags"),
- LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
- LOG_FORMAT(ESC, "HBBBHHHHHHfH", "Counter,NumESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
- LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
- LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
- LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
- LOG_FORMAT(TELE, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf"),
- LOG_FORMAT(ESTM, "ffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,n_states,states_nan,cov_nan,kgain_nan"),
- LOG_FORMAT(PWR, "fffBBBBB", "Periph_5V,Servo_5V,RSSI,USB_OK,BRICK_OK,SRV_OK,PERIPH_OC,HIPWR_OC"),
+ LOG_FORMAT(ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
+ LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
+ LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
+ LOG_FORMAT(LPOS, "ffffffffLLfBBBB", "X,Y,Z,dist,distR,VX,VY,VZ,RLat,RLon,RAlt,XYFlg,ZFlg,LFlg,GFlg"),
+ LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
+ LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
+ LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
+ LOG_FORMAT(STAT, "BBfBB", "MainState,ArmState,BatRem,BatWarn,Landed"),
+ LOG_FORMAT(RC, "ffffffffBB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count,SignalLost"),
+ LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
+ LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
+ LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
+ LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
+ LOG_FORMAT(GPOS, "LLfffffB", "Lat,Lon,Alt,VelN,VelE,VelD,BaroAlt,Flags"),
+ LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
+ LOG_FORMAT(ESC, "HBBBHHHHHHfH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
+ LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
+ LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
+ LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
+ LOG_FORMAT(TELE, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf"),
+ LOG_FORMAT(ESTM, "ffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,nStat,statNaN,covNaN,kGainNaN"),
+ LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
+ LOG_FORMAT(VICN, "ffffff", "X,Y,Z,Roll,Pitch,Yaw"),
/* system-level messages, ID >= 0x80 */
/* FMT: don't write format of format message, it's useless */
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index c8a589bb7..90675bb2e 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -127,7 +127,7 @@ ORB_DEFINE(position_setpoint_triplet, struct position_setpoint_triplet_s);
ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setpoint_s);
#include "topics/mission.h"
-ORB_DEFINE(mission, struct mission_s);
+ORB_DEFINE(offboard_mission, struct mission_s);
ORB_DEFINE(onboard_mission, struct mission_s);
#include "topics/mission_result.h"
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 9594c4c6a..ef4bc1def 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -105,7 +105,7 @@ struct mission_s
*/
/* register this as object request broker structure */
-ORB_DECLARE(mission);
+ORB_DECLARE(offboard_mission);
ORB_DECLARE(onboard_mission);
#endif