aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp2
-rw-r--r--src/modules/mavlink/mavlink_main.cpp80
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp90
-rw-r--r--src/modules/mavlink/mavlink_receiver.h2
4 files changed, 113 insertions, 61 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 6c2c03070..74deda8cc 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -129,7 +129,7 @@ extern struct system_load_s system_load;
#define POSITION_TIMEOUT (2 * 1000 * 1000) /**< consider the local or global position estimate invalid after 600ms */
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
#define RC_TIMEOUT 500000
-#define DL_TIMEOUT 5 * 1000* 1000
+#define DL_TIMEOUT (10 * 1000 * 1000)
#define OFFBOARD_TIMEOUT 500000
#define DIFFPRESS_TIMEOUT 2000000
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 408605939..976b6d4d5 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -134,44 +134,44 @@ Mavlink::Mavlink() :
_mode(MAVLINK_MODE_NORMAL),
_channel(MAVLINK_COMM_0),
_logbuffer {},
- _total_counter(0),
- _receive_thread {},
- _verbose(false),
- _forwarding_on(false),
- _passing_on(false),
- _ftp_on(false),
- _uart_fd(-1),
- _baudrate(57600),
- _datarate(1000),
- _datarate_events(500),
- _rate_mult(1.0f),
- _mavlink_param_queue_index(0),
- mavlink_link_termination_allowed(false),
- _subscribe_to_stream(nullptr),
- _subscribe_to_stream_rate(0.0f),
- _flow_control_enabled(true),
- _last_write_success_time(0),
- _last_write_try_time(0),
- _bytes_tx(0),
- _bytes_txerr(0),
- _bytes_rx(0),
- _bytes_timestamp(0),
- _rate_tx(0.0f),
- _rate_txerr(0.0f),
- _rate_rx(0.0f),
- _rstatus {},
- _message_buffer {},
- _message_buffer_mutex {},
- _send_mutex {},
- _param_initialized(false),
- _param_system_id(0),
- _param_component_id(0),
- _param_system_type(0),
- _param_use_hil_gps(0),
-
- /* performance counters */
- _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
- _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
+ _total_counter(0),
+ _receive_thread {},
+ _verbose(false),
+ _forwarding_on(false),
+ _passing_on(false),
+ _ftp_on(false),
+ _uart_fd(-1),
+ _baudrate(57600),
+ _datarate(1000),
+ _datarate_events(500),
+ _rate_mult(1.0f),
+ _mavlink_param_queue_index(0),
+ mavlink_link_termination_allowed(false),
+ _subscribe_to_stream(nullptr),
+ _subscribe_to_stream_rate(0.0f),
+ _flow_control_enabled(true),
+ _last_write_success_time(0),
+ _last_write_try_time(0),
+ _bytes_tx(0),
+ _bytes_txerr(0),
+ _bytes_rx(0),
+ _bytes_timestamp(0),
+ _rate_tx(0.0f),
+ _rate_txerr(0.0f),
+ _rate_rx(0.0f),
+ _rstatus {},
+ _message_buffer {},
+ _message_buffer_mutex {},
+ _send_mutex {},
+ _param_initialized(false),
+ _param_system_id(0),
+ _param_component_id(0),
+ _param_system_type(0),
+ _param_use_hil_gps(0),
+
+ /* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
+ _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
{
fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl;
@@ -217,6 +217,8 @@ Mavlink::Mavlink() :
errx(1, "instance ID is out of range");
break;
}
+
+ _rstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
}
Mavlink::~Mavlink()
@@ -1653,6 +1655,8 @@ Mavlink::display_status()
printf("\tGCS heartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time));
}
+ printf("\tmavlink chan: #%u\n", _channel);
+
if (_rstatus.timestamp > 0) {
printf("\ttype:\t\t");
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index c0fae0a2f..a602344fd 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -112,7 +112,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
- _radio_status_available(false),
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
_hil_frames(0),
_old_timestamp(0),
@@ -137,6 +136,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_command_long(msg);
break;
+ case MAVLINK_MSG_ID_COMMAND_INT:
+ handle_message_command_int(msg);
+ break;
+
case MAVLINK_MSG_ID_OPTICAL_FLOW:
handle_message_optical_flow(msg);
break;
@@ -277,6 +280,62 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
}
void
+MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
+{
+ /* command */
+ mavlink_command_int_t cmd_mavlink;
+ mavlink_msg_command_int_decode(msg, &cmd_mavlink);
+
+ if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
+ || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
+ //check for MAVLINK terminate command
+ if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
+ /* This is the link shutdown command, terminate mavlink */
+ warnx("terminated by remote command");
+ fflush(stdout);
+ usleep(50000);
+
+ /* terminate other threads and this thread */
+ _mavlink->_task_should_exit = true;
+
+ } else {
+
+ if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
+ warnx("ignoring CMD spoofed with same SYS/COMP (%d/%d) ID",
+ mavlink_system.sysid, mavlink_system.compid);
+ return;
+ }
+
+ struct vehicle_command_s vcmd;
+ memset(&vcmd, 0, sizeof(vcmd));
+
+ /* Copy the content of mavlink_command_int_t cmd_mavlink into command_t cmd */
+ vcmd.param1 = cmd_mavlink.param1;
+ vcmd.param2 = cmd_mavlink.param2;
+ vcmd.param3 = cmd_mavlink.param3;
+ vcmd.param4 = cmd_mavlink.param4;
+ /* these are coordinates as 1e7 scaled integers to work around the 32 bit floating point limits */
+ vcmd.param5 = ((double)cmd_mavlink.x) / 1e7;
+ vcmd.param6 = ((double)cmd_mavlink.y) / 1e7;
+ vcmd.param7 = cmd_mavlink.z;
+ // XXX do proper translation
+ vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
+ vcmd.target_system = cmd_mavlink.target_system;
+ vcmd.target_component = cmd_mavlink.target_component;
+ vcmd.source_system = msg->sysid;
+ vcmd.source_component = msg->compid;
+
+ if (_cmd_pub < 0) {
+ _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
+
+ } else {
+ orb_publish(ORB_ID(vehicle_command), _cmd_pub, &vcmd);
+ }
+ }
+ }
+}
+
+void
MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
{
/* optical flow */
@@ -430,9 +489,6 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
} else {
orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
}
-
- /* this means that heartbeats alone won't be published to the radio status no more */
- _radio_status_available = true;
}
}
@@ -474,25 +530,17 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
struct telemetry_status_s &tstatus = _mavlink->get_rx_status();
- hrt_abstime tnow = hrt_absolute_time();
-
- /* always set heartbeat, publish only if telemetry link not up */
- tstatus.heartbeat_time = tnow;
-
- /* if no radio status messages arrive, lets at least publish that heartbeats were received */
- if (!_radio_status_available) {
+ /* set heartbeat time and topic time and publish -
+ * the telem status also gets updated on telemetry events
+ */
+ tstatus.timestamp = hrt_absolute_time();
+ tstatus.heartbeat_time = tstatus.timestamp;
- tstatus.timestamp = tnow;
- /* telem_time indicates the timestamp of a telemetry status packet and we got none */
- tstatus.telem_time = 0;
- tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
+ if (_telemetry_status_pub < 0) {
+ _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
- if (_telemetry_status_pub < 0) {
- _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
-
- } else {
- orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
- }
+ } else {
+ orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
}
}
}
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 014193100..91125736c 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -110,6 +110,7 @@ private:
void handle_message(mavlink_message_t *msg);
void handle_message_command_long(mavlink_message_t *msg);
+ void handle_message_command_int(mavlink_message_t *msg);
void handle_message_optical_flow(mavlink_message_t *msg);
void handle_message_set_mode(mavlink_message_t *msg);
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
@@ -151,7 +152,6 @@ private:
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
- bool _radio_status_available;
int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;