mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 12:57:34 +08:00
MAVLink: better output handling
This commit is contained in:
@@ -427,6 +427,8 @@ public:
|
||||
|
||||
bool accepting_commands() { return true; /* non-trivial side effects ((!_config_link_on) || (_mode == MAVLINK_MODE_CONFIG));*/ }
|
||||
|
||||
bool verbose() { return _verbose; }
|
||||
|
||||
int get_data_rate() { return _datarate; }
|
||||
void set_data_rate(int rate) { if (rate > 0) { _datarate = rate; } }
|
||||
|
||||
|
||||
@@ -458,11 +458,17 @@ protected:
|
||||
/* only send commands for other systems/components, don't forward broadcast commands */
|
||||
if ((cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) &&
|
||||
(cmd.target_component != MAV_COMP_ID_ALL)) {
|
||||
PX4_INFO("sending command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
|
||||
|
||||
if (_mavlink->verbose()) {
|
||||
PX4_INFO("sending command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
|
||||
}
|
||||
|
||||
MavlinkCommandSender::instance().handle_vehicle_command(cmd, _mavlink->get_channel());
|
||||
|
||||
} else {
|
||||
PX4_INFO("not forwarding command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
|
||||
if (_mavlink->verbose()) {
|
||||
PX4_INFO("not forwarding command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -87,7 +87,7 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
|
||||
_mission_result_sub(-1),
|
||||
_offboard_mission_pub(nullptr),
|
||||
_slow_rate_limiter(100 * 1000), // Rate limit sending of the current WP sequence to 10 Hz
|
||||
_verbose(false),
|
||||
_verbose(mavlink->verbose()),
|
||||
_mavlink(mavlink)
|
||||
{
|
||||
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
|
||||
@@ -385,10 +385,14 @@ MavlinkMissionManager::send(const hrt_abstime now)
|
||||
&& hrt_elapsed_time(&_time_last_sent) > _retry_timeout) {
|
||||
if (_transfer_seq == 0) {
|
||||
/* try to send items count again after timeout */
|
||||
if (_verbose) { warnx("WPM: send count timeout"); }
|
||||
|
||||
send_mission_count(_transfer_partner_sysid, _transfer_partner_compid, _transfer_count);
|
||||
|
||||
} else {
|
||||
/* try to send item again after timeout */
|
||||
if (_verbose) { warnx("WPM: item re-send timeout"); }
|
||||
|
||||
send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq - 1);
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user