Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

High Latency Telemetry Support #8582

Merged
merged 48 commits into from
Apr 11, 2018
Merged

Conversation

acfloria
Copy link
Contributor

@acfloria acfloria commented Jan 4, 2018

Improvements of the Iridiumsbd Driver and add a fallback to the high latency telemetry.

The changes in more details:

  • Iridiumsbd Driver
    • Add parameter for session timeout, read interval, and stacking time
    • Add VERBOSE_INFO macro
    • Add sbd session timeout
    • Update heartbeat after successful SBD session and fill it in the telemetry_status message
    • Check test command to avoid being stuck in the test state
    • Make class variables private
    • Reorder function so that in the header and source file they have the same order
    • Fix updating the rssi at a constant rate when no sbd session is scheduled
    • Add variable timout to read_at function
  • Commander Module
    • Add the logic for the high latency telemetry fallback
  • Mavlink Module
    • Enable/disable transmitting from all mavlink instances of a certain type using a vehicle_command uorb message.

Switching Logic:

  • Only activate the high latency telemetry if the vehicle is armed.
  • If all low latency links are lost and a high latency link is present:
    • Activate the high latency telemetry
  • If the high latency is active and a low latency link is regained:
    • Deactivate the high latency telemetry
  • If all low latency links are lost and a high latency link is not present:
    • Telemetry failsafe action
  • If all low and high latency links are lost:
    • Telemetry failsafe action
  • If a low latency link is regained after all low and high latency links were lost:
    • Deactivate the high latency telemetry

@TSC21
Copy link
Member

TSC21 commented Jan 4, 2018

@acfloria this seems very interesting. Question: based on the latest iteration that's ongoing on Mavlink form HIGH_LATENCY msg, would this be ready to actually establish a two-way communication instead of just having the FCU sending the data?

@dagar
Copy link
Member

dagar commented Jan 4, 2018

Generally looks good. I'll review in detail and test on my side. What testing have you done with real hardware so far?

@TSC21 if you have everything it would be great to test this as well.

mavlink_log_critical(&mavlink_log_pub, "ALL LOW LATENCY DATA LINKS LOST, ACTIVATING HIGH LATENCY LINK");
vehicle_command_s vehicle_cmd;
vehicle_cmd.command = vehicle_command_s::VEHICLE_CMD_MAVLINK_ENABLE_SENDING;
vehicle_cmd.param1 = 6;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

magic numbers

if (vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_MAVLINK_ENABLE_SENDING) {
if (_mode == (int)round(vehicle_cmd.param1)) {
if (_transmitting_enabled != (int)vehicle_cmd.param2) {
if ((int)vehicle_cmd.param2)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

braces

if ((int)vehicle_cmd.param2)
PX4_INFO("Enable transmitting with mavlink instance of type %s on device %s", mavlink_mode_str(_mode), _device_name);
else
PX4_INFO("Disable transmitting with mavlink instance of type %s on device %s", mavlink_mode_str(_mode), _device_name);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

braces

@dagar
Copy link
Member

dagar commented Jan 4, 2018

I'm wondering if we need to generalize the link loss handling for all link types, and possibly push more of it into the mavlink module.
#7985

@acfloria
Copy link
Contributor Author

I tested the switching logic and testing the signal strength with the real hardware. I haven't sent any message over the link as I do not have a line rented yet. I will test transmitting data when the overall system is ready for it (Mavlink and QGC)

@acfloria acfloria force-pushed the feature/telemetry_fallback branch from 71f290a to a15a1fa Compare January 11, 2018 10:01
@dagar dagar added this to the Release v1.8.0 milestone Jan 11, 2018
@acfloria acfloria changed the title [WIP] High Latency Telemetry Logic [WIP] High Latency Telemetry Support Jan 25, 2018
@acfloria acfloria force-pushed the feature/telemetry_fallback branch from a15a1fa to 72b184e Compare January 25, 2018 15:44
@TSC21
Copy link
Member

TSC21 commented Jan 27, 2018

@acfloria can you please rebase?

Copy link
Member

@TSC21 TSC21 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It looks good to me. I can test this when I have my line rental activated. This should be synced also with the update on the HIGH_LATENCY Mavlink msg.

@@ -62,6 +62,7 @@ bool rc_signal_lost # true if RC reception lost
uint8 rc_input_mode # set to 1 to disable the RC input, 2 to enable manual control to RC in mapping.

bool data_link_lost # datalink to GCS lost
bool high_latency_data_link_active # all low latency datalinks to GCS lost
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

indentation

@@ -85,54 +85,14 @@ const char *satcom_state_string[4] = {"STANDBY", "SIGNAL CHECK", "SBD SESSION",

extern "C" __EXPORT int iridiumsbd_main(int argc, char *argv[]);

#define SATCOM_TX_BUF_LEN 50 // TX buffer size - maximum for a SBD MO message is 340, but billed per 50
#define SATCOM_RX_MSG_BUF_LEN 300 // RX buffer size for MT messages
#define SATCOM_TX_BUF_LEN 340 // TX buffer size - maximum for a SBD MO message is 340, but billed per 50
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

indentation

* @max 300
* @group Iridium SBD
*/
PARAM_DEFINE_INT32(ISBD_SBD_TIMEOUT, 60);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this the time for "datalink" timeout on the high latency link?

* @min 60
* @max 3600
*/
PARAM_DEFINE_INT32(COM_HLDL_LOSS_T, 120);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I got my answer here.

@@ -476,6 +476,7 @@ class Mavlink

private:
int _instance_id;
bool _transmitting_enabled;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

indentation

@TSC21
Copy link
Member

TSC21 commented Jan 27, 2018

@acfloria what's the deal with QRT that lead you to add the conditions?

@acfloria
Copy link
Contributor Author

It looks good to me. I can test this when I have my line rental activated. This should be synced also with the update on the HIGH_LATENCY Mavlink msg.

I will also do some tests and rent a line once the HIGH_LATENCY message is merged on mavlink.

@acfloria what's the deal with QRT that lead you to add the conditions?

It is necessary, as for one build version mavlink is not used. I do not recall by heart which version.

@TSC21
Copy link
Member

TSC21 commented Jan 30, 2018

@acfloria were you able to test this in the mean time with the new msg?

@acfloria acfloria force-pushed the feature/telemetry_fallback branch from 72b184e to aabfbd7 Compare January 30, 2018 17:04
@acfloria
Copy link
Contributor Author

@TSC21 I just added the support for it and tested it in SITL.

@acfloria acfloria force-pushed the feature/telemetry_fallback branch from e0745ed to d8b7427 Compare January 31, 2018 14:23
@TSC21
Copy link
Member

TSC21 commented Feb 5, 2018

@TSC21 I just added the support for it and tested it in SITL.

I should be able to test this on my end with real HW this week.

@acfloria acfloria force-pushed the feature/telemetry_fallback branch 2 times, most recently from a2c321b to f7f4276 Compare February 12, 2018 09:54
@acfloria acfloria force-pushed the feature/telemetry_fallback branch from f7f4276 to 383e924 Compare February 26, 2018 14:54
@acfloria acfloria force-pushed the feature/telemetry_fallback branch from 06697af to 7d8e591 Compare March 9, 2018 12:13
@vayu-julie
Copy link

I tested this on a Pixhawk 3 Pro with a RockBlock Mk2 on a bench. The telemetry switching works as outlined in the switching logic.

@acfloria acfloria changed the title [WIP] High Latency Telemetry Support High Latency Telemetry Support Mar 15, 2018
@acfloria
Copy link
Contributor Author

@dagar this PR has been extensively tested with real hardware. Can you review the code?

@acfloria acfloria force-pushed the feature/telemetry_fallback branch from 086b691 to c1cbaee Compare March 23, 2018 13:13
acfloria added 9 commits April 4, 2018 15:28
- Check if changing to a non standby state if the current state is the standy state and no change is already scheduled.
- Add prefix _ to all class variables
Due to the old heartbeat of the high latency telemetry when activating it after flying sufficiently long in normal telemetry it is first detected as lost until the first message is sent.
By updating the heartbeat to the current time on switching this issue is avoided.

Also includes a small style fix for the HIGH_LATENCY2 stream
@acfloria acfloria force-pushed the feature/telemetry_fallback branch from 02b248d to d4fd44d Compare April 4, 2018 13:39
Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've had a look over the first part of the PR and remarked what caught my eye. Generally looks good.
I'll review the mavlink changes in a second pass.

if (*buffer == MAVLINK_PACKAGE_START) {
if (SATCOM_TX_BUF_LEN - _tx_buf_write_idx - (*(buffer + 1) + 8) < 0) {
_tx_buf_write_idx = 0;
mavlink_log_critical(&_mavlink_log_pub, "Deleting full TX buffer before writing new message");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this intended to be user-facing or just to debug?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is just to debug as in high latency telemetry the status texts are not transmitted.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, but it should not go into a release, as a user has no idea what this means.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agreed. I am filling the tx_buf field of the telemetry_status correctly so it can be observed by that variable if a reset happens. However, I think for debugging it might be useful to have a status message of the driver where the status can be logged in more details. I will add that as a future PR after this one here is merged.


// check if there is enough space for the incoming mavlink message
if (buflen == 6) {
if (*buffer == MAVLINK_PACKAGE_START) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is fragile: it assumes mavlink 1 and a certain write pattern from mavlink (the buflen == 6 check)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree, that is why I added the check just after that one to catch anything which does not fit into that scheme.
However, in high latency mavlink 1 should be used because it assures that the HIGH_LATENCY2 message is 50 bytes. This is desired as for example rockblock bills in 50 byte increments.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd still rather have it done properly. You can look at how protocol_splitter does it for example: https://github.com/PX4/Firmware/blob/master/src/drivers/protocol_splitter/protocol_splitter.cpp#L358.
At the very least it should be documented that this is a hacky solution and nothing important must depend on this.

Does a user know that he/she should be using mavkink 1 with this device? Is it enforced somewhere?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I adopted it to the way the protocol_splitter is doing it.

Mavlink 1 is not enforced but encouraged as the design of the HIGH_LATENCY2 stream was to create a 50 byte status message. Using Mavlink 2 this goal cannot be met due to the larger header. I added a note in the header file. Once the full high latency telemetry together with QGC is working there should be a documentation about it for example in the dev guide where this information should also be written.

int32_t datalink_loss_timeout, int32_t datalink_regain_timeout, bool *status_changed);

// telemetry variables
int _telemetry_subs[ORB_MULTI_MAX_INSTANCES] = {};
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you create a separate struct for these? Then you need only one array and can use a constructor or member initializer to initialize the fields

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point. I added that struct.

@@ -988,6 +990,7 @@ Mavlink::send_bytes(const uint8_t *buf, unsigned packet_len)
return;
}


Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you please avoid adding unnecessary newlines?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure, removed.

Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I realize I have plenty of remarks, but the overall structure looks good.


if (cmd_sub->update(&cmd_time, &vehicle_cmd)) {
if ((vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY) && (_mode == MAVLINK_MODE_IRIDIUM)) {
if ((vehicle_cmd.param1 > 0.5f)) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

unnecessary brackets (more below)

_transmitting_enabled = true;
_transmitting_enabled_commanded = true;

} else if ((vehicle_cmd.param1 <= 0.5f)) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just } else { is enough

struct vehicle_command_s vehicle_cmd;

if (cmd_sub->update(&cmd_time, &vehicle_cmd)) {
if ((vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY) && (_mode == MAVLINK_MODE_IRIDIUM)) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if this comes from external, someone needs to send an ack. It can be done from commander.

@@ -2201,7 +2236,11 @@ Mavlink::task_main(int argc, char *argv[])
msg.target_component = command_ack.target_component;
current_command_ack = command_ack.command;

// TODO: always transmit the acknowledge once it is only sent over the instance the command is received
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you fix this?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have an idea how to fix it, but as it potentially can break things and is not an trivial change I would prefer to do it in a separate PR.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok that's fine.

if (*buffer == MAVLINK_PACKAGE_START) {
if (SATCOM_TX_BUF_LEN - _tx_buf_write_idx - (*(buffer + 1) + 8) < 0) {
_tx_buf_write_idx = 0;
mavlink_log_critical(&_mavlink_log_pub, "Deleting full TX buffer before writing new message");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, but it should not go into a release, as a user has no idea what this means.


update_tecs_status(_update_rate_filtered);

update_battery_status(_update_rate_filtered);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since you're passing a class member _update_rate_filtered, you can avoid adding an argument and use _update_rate_filtered directly in update_battery_status

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

@@ -103,6 +103,11 @@ class MavlinkStream
virtual bool send(const hrt_abstime t) = 0;
#endif

/**
* Function to collect/update data for the streams when update() is called.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you document this a bit more? Like saying that it's called at a high rate, independent from the configured stream rate.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

@@ -3929,22 +3941,22 @@ class MavlinkStreamMountOrientation : public MavlinkStream
}
};

class MavlinkStreamHighLatency : public MavlinkStream
class MavlinkStreamHighLatency2 : public MavlinkStream
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

since this is so large, it's almost worth splitting it into a separate file.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure, I moved it to a separate file

if (sent) {
_last_sent = (interval > 0) ? _last_sent + interval : t;
_last_sent = ((interval > 0) && ((int64_t)(1.5 * interval) > dt)) ? _last_sent + interval : t;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you use 1.5f to avoid converting to double?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed.

// If the interval is non-zero and dt is smaller than 1.5 times the interval
// do not use the actual time but increment at a fixed rate, so that processing delays do not
// distort the average rate. The check of the maximum interval is done to ensure that after a long time
// not sending anything multiple messages in a short time are sent.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The check of the maximum interval is done to ensure that after a long time not sending anything multiple messages in a short time are sent.

Should this not be more like: The check of the maximum interval is done to ensure that after a long time not sending anything, sending multiple messages in a short time is avoided.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure, you are right. Changed it to your version

@acfloria
Copy link
Contributor Author

@bkueng I implemented the changes you requested. Can you review the fixes again?

Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the update.

Yes, but this is also currently the default behavior. Any acknowledge will be sent over every instance.

I meant that multiple uorb acks are published. But since you moved this to commander, it's correct now.

Unfortunately not, as this function is used with fields of a packed struct and therefore won't compile using a reference.

Uh, but this is not good, and the compiler complains for good reasons. Passing the member of a packed struct as a pointer can lead to memory access alignment problems (and crashes).

char _test_command[32];
hrt_abstime _test_timer = 0;

uint8_t _rx_command_buf[SATCOM_RX_COMMAND_BUF_LEN] = {0};
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I suggest you change it to = {}. {0} is confusing, as for example using {1} would lead to only the first element being 1 and all others 0.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed

#include "mavlink_simple_analyzer.h"
#include "mavlink_stream.h"

#ifndef MAVLINK_HIGH_LATENCY2_H_
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I suggest you use #pragma once instead

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed

@@ -2201,7 +2236,11 @@ Mavlink::task_main(int argc, char *argv[])
msg.target_component = command_ack.target_component;
current_command_ack = command_ack.command;

// TODO: always transmit the acknowledge once it is only sent over the instance the command is received
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok that's fine.

…e function

- Addional small cleanup of the iridium driver and the include guards of mavlink module header files
Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good to go now!

@bkueng
Copy link
Member

bkueng commented Apr 11, 2018

@dagar circleci seems to be broken

@bkueng bkueng merged commit 0caa4dc into PX4:master Apr 11, 2018
@acfloria acfloria deleted the feature/telemetry_fallback branch July 10, 2018 13:12
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants