mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 11:06:04 +08:00
MAVLink app: Add option to configure broadcast, default to off
This commit is contained in:
@@ -237,12 +237,15 @@ Mavlink::Mavlink() :
|
|||||||
_message_buffer_mutex {},
|
_message_buffer_mutex {},
|
||||||
_send_mutex {},
|
_send_mutex {},
|
||||||
_param_initialized(false),
|
_param_initialized(false),
|
||||||
_param_system_id(0),
|
_logging_enabled(false),
|
||||||
_param_component_id(0),
|
_broadcast_mode(Mavlink::BROADCAST_MODE_OFF),
|
||||||
_param_radio_id(0),
|
_param_system_id(PARAM_INVALID),
|
||||||
_param_system_type(MAV_TYPE_FIXED_WING),
|
_param_component_id(PARAM_INVALID),
|
||||||
_param_use_hil_gps(0),
|
_param_radio_id(PARAM_INVALID),
|
||||||
_param_forward_externalsp(0),
|
_param_system_type(PARAM_INVALID),
|
||||||
|
_param_use_hil_gps(PARAM_INVALID),
|
||||||
|
_param_forward_externalsp(PARAM_INVALID),
|
||||||
|
_param_broadcast(PARAM_INVALID),
|
||||||
_system_type(0),
|
_system_type(0),
|
||||||
|
|
||||||
/* performance counters */
|
/* performance counters */
|
||||||
@@ -539,6 +542,7 @@ void Mavlink::mavlink_update_system(void)
|
|||||||
_param_system_type = param_find("MAV_TYPE");
|
_param_system_type = param_find("MAV_TYPE");
|
||||||
_param_use_hil_gps = param_find("MAV_USEHILGPS");
|
_param_use_hil_gps = param_find("MAV_USEHILGPS");
|
||||||
_param_forward_externalsp = param_find("MAV_FWDEXTSP");
|
_param_forward_externalsp = param_find("MAV_FWDEXTSP");
|
||||||
|
_param_broadcast = param_find("MAV_BROADCAST");
|
||||||
|
|
||||||
/* test param - needs to be referenced, but is unused */
|
/* test param - needs to be referenced, but is unused */
|
||||||
(void)param_find("MAV_TEST_PAR");
|
(void)param_find("MAV_TEST_PAR");
|
||||||
@@ -597,6 +601,8 @@ void Mavlink::mavlink_update_system(void)
|
|||||||
int32_t forward_externalsp;
|
int32_t forward_externalsp;
|
||||||
param_get(_param_forward_externalsp, &forward_externalsp);
|
param_get(_param_forward_externalsp, &forward_externalsp);
|
||||||
|
|
||||||
|
param_get(_param_broadcast, &_broadcast_mode);
|
||||||
|
|
||||||
_forward_externalsp = (bool)forward_externalsp;
|
_forward_externalsp = (bool)forward_externalsp;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -889,7 +895,7 @@ Mavlink::send_packet()
|
|||||||
struct telemetry_status_s &tstatus = get_rx_status();
|
struct telemetry_status_s &tstatus = get_rx_status();
|
||||||
|
|
||||||
/* resend message via broadcast if no valid connection exists */
|
/* resend message via broadcast if no valid connection exists */
|
||||||
if ((_mode != MAVLINK_MODE_ONBOARD) &&
|
if ((_mode != MAVLINK_MODE_ONBOARD) && broadcast_enabled() &&
|
||||||
(!get_client_source_initialized()
|
(!get_client_source_initialized()
|
||||||
|| (hrt_elapsed_time(&tstatus.heartbeat_time) > 3 * 1000 * 1000))) {
|
|| (hrt_elapsed_time(&tstatus.heartbeat_time) > 3 * 1000 * 1000))) {
|
||||||
|
|
||||||
@@ -2475,6 +2481,26 @@ Mavlink::stream_command(int argc, char *argv[])
|
|||||||
return OK;
|
return OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Mavlink::set_boot_complete()
|
||||||
|
{
|
||||||
|
_boot_complete = true;
|
||||||
|
|
||||||
|
#ifdef __PX4_POSIX
|
||||||
|
Mavlink *inst;
|
||||||
|
LL_FOREACH(::_mavlink_instances, inst) {
|
||||||
|
if ((inst->get_mode() != MAVLINK_MODE_ONBOARD) &&
|
||||||
|
(!inst->broadcast_enabled()) &&
|
||||||
|
((inst->get_protocol() == UDP) || (inst->get_protocol() == TCP))) {
|
||||||
|
printf("\n\n ********** NETWORK BROADCAST NOT ENABLED **********\n" \
|
||||||
|
" The drone will only connect to localhost (excluding VMs).\n" \
|
||||||
|
" Run 'pxh> param set MAV_BROADCAST 1' to enable.\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
static void usage()
|
static void usage()
|
||||||
{
|
{
|
||||||
warnx("usage: mavlink {start|stop|stream} [-d device] [-u network_port] [-o remote_port] [-t partner_ip] [-b baudrate]\n\t[-r rate][-m mode] [-s stream] [-f] [-p] [-v] [-w] [-x]");
|
warnx("usage: mavlink {start|stop|stream} [-d device] [-u network_port] [-o remote_port] [-t partner_ip] [-b baudrate]\n\t[-r rate][-m mode] [-s stream] [-f] [-p] [-v] [-w] [-x]");
|
||||||
|
|||||||
@@ -164,6 +164,11 @@ public:
|
|||||||
MAVLINK_MODE_CONFIG
|
MAVLINK_MODE_CONFIG
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum BROADCAST_MODE {
|
||||||
|
BROADCAST_MODE_OFF = 0,
|
||||||
|
BROADCAST_MODE_ON
|
||||||
|
};
|
||||||
|
|
||||||
void set_mode(enum MAVLINK_MODE);
|
void set_mode(enum MAVLINK_MODE);
|
||||||
enum MAVLINK_MODE get_mode() { return _mode; }
|
enum MAVLINK_MODE get_mode() { return _mode; }
|
||||||
|
|
||||||
@@ -181,13 +186,15 @@ public:
|
|||||||
|
|
||||||
void set_config_link_on(bool on) { _config_link_on = on; }
|
void set_config_link_on(bool on) { _config_link_on = on; }
|
||||||
|
|
||||||
|
bool broadcast_enabled() { return _broadcast_mode > BROADCAST_MODE_OFF; }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Set the boot complete flag on all instances
|
* Set the boot complete flag on all instances
|
||||||
*
|
*
|
||||||
* Setting the flag unblocks parameter transmissions, which are gated
|
* Setting the flag unblocks parameter transmissions, which are gated
|
||||||
* beforehand to ensure that the system is fully initialized.
|
* beforehand to ensure that the system is fully initialized.
|
||||||
*/
|
*/
|
||||||
static void set_boot_complete() { _boot_complete = true; }
|
static void set_boot_complete();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the free space in the transmit buffer
|
* Get the free space in the transmit buffer
|
||||||
@@ -504,6 +511,7 @@ private:
|
|||||||
|
|
||||||
bool _param_initialized;
|
bool _param_initialized;
|
||||||
bool _logging_enabled;
|
bool _logging_enabled;
|
||||||
|
uint32_t _broadcast_mode;
|
||||||
|
|
||||||
param_t _param_system_id;
|
param_t _param_system_id;
|
||||||
param_t _param_component_id;
|
param_t _param_component_id;
|
||||||
@@ -512,6 +520,7 @@ private:
|
|||||||
param_t _param_system_type;
|
param_t _param_system_type;
|
||||||
param_t _param_use_hil_gps;
|
param_t _param_use_hil_gps;
|
||||||
param_t _param_forward_externalsp;
|
param_t _param_forward_externalsp;
|
||||||
|
param_t _param_broadcast;
|
||||||
|
|
||||||
unsigned _system_type;
|
unsigned _system_type;
|
||||||
static bool _config_link_on;
|
static bool _config_link_on;
|
||||||
|
|||||||
@@ -99,6 +99,18 @@ PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
|
|||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
|
PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Broadcast heartbeats on local network
|
||||||
|
*
|
||||||
|
* This allows a ground control station to automatically find the drone
|
||||||
|
* on the local network.
|
||||||
|
*
|
||||||
|
* @value 0 Never broadcast
|
||||||
|
* @value 1 Always broadcast
|
||||||
|
* @group MAVLink
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_INT32(MAV_BROADCAST, 0);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Test parameter
|
* Test parameter
|
||||||
*
|
*
|
||||||
|
|||||||
Reference in New Issue
Block a user