Skip to content

Commit

Permalink
Treat 3DR radio as generic link type
Browse files Browse the repository at this point in the history
  • Loading branch information
Nico van Duijn committed Jan 29, 2020
1 parent d946b79 commit 514fb7d
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 27 deletions.
9 changes: 4 additions & 5 deletions msg/telemetry_status.msg
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
uint8 LINK_TYPE_GENERIC = 0
uint8 LINK_TYPE_3DR_RADIO = 1
uint8 LINK_TYPE_UBIQUITY_BULLET = 2
uint8 LINK_TYPE_WIRE = 3
uint8 LINK_TYPE_USB = 4
uint8 LINK_TYPE_IRIDIUM = 5
uint8 LINK_TYPE_UBIQUITY_BULLET = 1
uint8 LINK_TYPE_WIRE = 2
uint8 LINK_TYPE_USB = 3
uint8 LINK_TYPE_IRIDIUM = 4

# MAV_COMPONENT (fill in as needed)
uint8 COMPONENT_ID_ALL = 0
Expand Down
25 changes: 10 additions & 15 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1550,11 +1550,11 @@ void
Mavlink::update_radio_status(const radio_status_s &radio_status)
{
_rstatus = radio_status;
_radio_status_available = true;

if (_use_software_mav_throttling) {

/* check hardware limits */
_radio_status_available = true;
_radio_status_critical = (radio_status.txbuf < RADIO_BUFFER_LOW_PERCENTAGE);

if (radio_status.txbuf < RADIO_BUFFER_CRITICAL_LOW_PERCENTAGE) {
Expand Down Expand Up @@ -2258,7 +2258,7 @@ Mavlink::task_main(int argc, char *argv[])
#endif // CONFIG_NET
}

check_radio_config();
configure_3dr_radio();

if (status_sub->update(&status_time, &status)) {
/* switch HIL mode if required */
Expand Down Expand Up @@ -2608,11 +2608,10 @@ void Mavlink::publish_telemetry_status()
_telem_status_pub.publish(_tstatus);
}

void Mavlink::check_radio_config()
void Mavlink::configure_3dr_radio()
{
/* radio config check */
if (_uart_fd >= 0 && _param_mav_radio_id.get() != 0
&& _tstatus.type == telemetry_status_s::LINK_TYPE_3DR_RADIO) {
if (_uart_fd >= 0 && _param_3dr_radio_id.get() != 0) {
/* request to configure radio and radio is present */
FILE *fs = fdopen(_uart_fd, "w");

Expand Down Expand Up @@ -2655,8 +2654,8 @@ void Mavlink::check_radio_config()
}

/* reset param and save */
_param_mav_radio_id.set(0);
_param_mav_radio_id.commit_no_notification();
_param_3dr_radio_id.set(0);
_param_3dr_radio_id.commit_no_notification();
}
}

Expand Down Expand Up @@ -2755,25 +2754,21 @@ Mavlink::display_status()

printf("\ttype:\t\t");

switch (_tstatus.type) {
case telemetry_status_s::LINK_TYPE_3DR_RADIO:
printf("3DR RADIO\n");
if (_radio_status_available) {
printf("RADIO Link\n");
printf("\t rssi:\t\t%d\n", _rstatus.rssi);
printf("\t remote rssi:\t%u\n", _rstatus.remote_rssi);
printf("\t txbuf:\t%u\n", _rstatus.txbuf);
printf("\t noise:\t%d\n", _rstatus.noise);
printf("\t remote noise:\t%u\n", _rstatus.remote_noise);
printf("\t rx errors:\t%u\n", _rstatus.rxerrors);
printf("\t fixed:\t%u\n", _rstatus.fix);
break;

case telemetry_status_s::LINK_TYPE_USB:
} else if (_is_usb_uart) {
printf("USB CDC\n");
break;

default:
} else {
printf("GENERIC LINK OR RADIO\n");
break;
}

} else {
Expand Down
8 changes: 4 additions & 4 deletions src/modules/mavlink/mavlink_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -663,7 +663,7 @@ class Mavlink : public ModuleParams
(ParamInt<px4::params::MAV_SYS_ID>) _param_mav_sys_id,
(ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id,
(ParamInt<px4::params::MAV_PROTO_VER>) _param_mav_proto_ver,
(ParamInt<px4::params::MAV_RADIO_ID>) _param_mav_radio_id,
(ParamInt<px4::params::MAV_3DR_RADIO_ID>) _param_3dr_radio_id,
(ParamInt<px4::params::MAV_TYPE>) _param_mav_type,
(ParamBool<px4::params::MAV_USEHILGPS>) _param_mav_usehilgps,
(ParamBool<px4::params::MAV_FWDEXTSP>) _param_mav_fwdextsp,
Expand Down Expand Up @@ -726,12 +726,12 @@ class Mavlink : public ModuleParams
void check_requested_subscriptions();

/**
* Check the configuration of a connected radio
* Reconfigure a 3DR radio if requested by MAV_3DR_RADIO_ID
*
* This convenience function allows to re-configure a connected
* radio without removing it from the main system harness.
* 3DR radio without removing it from the main system harness.
*/
void check_radio_config();
void configure_3dr_radio();

/**
* Update rate mult so total bitrate will be equal to _datarate.
Expand Down
8 changes: 5 additions & 3 deletions src/modules/mavlink/mavlink_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -59,18 +59,20 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 1);
PARAM_DEFINE_INT32(MAV_PROTO_VER, 0);

/**
* MAVLink Radio ID
* MAVLink 3DR Radio ID
*
* When non-zero the MAVLink app will attempt to configure the
* radio to this ID and re-set the parameter to 0. If the value
* 3DR radio to this ID and re-set the parameter to 0. If the value
* is negative it will reset the complete radio config to
* factory defaults.
*
* @note Only applies if this mavlink instance is going through a 3DR radio
*
* @group MAVLink
* @min -1
* @max 240
*/
PARAM_DEFINE_INT32(MAV_RADIO_ID, 0);
PARAM_DEFINE_INT32(MAV_3DR_RADIO_ID, 0);

/**
* MAVLink airframe type
Expand Down

0 comments on commit 514fb7d

Please sign in to comment.