Browse Source

MAVLink app: Make debug messages a compile time check

The debug messages are too verbose to be run in a production vehicle and inherently were something that should only be run in SITL / debug sessions on hardware. Switching the flag to the PX4_DEBUG() macro does not only make this more explicit, but also saves a lot of flash space that otherwise was consumed by the strings.
sbg
Lorenz Meier 7 years ago committed by Daniel Agar
parent
commit
6227139df1
  1. 45
      src/modules/mavlink/mavlink_main.cpp
  2. 18
      src/modules/mavlink/mavlink_main.h
  3. 8
      src/modules/mavlink/mavlink_messages.cpp
  4. 136
      src/modules/mavlink/mavlink_mission.cpp
  5. 4
      src/modules/mavlink/mavlink_mission.h
  6. 10
      src/modules/mavlink/mavlink_receiver.cpp

45
src/modules/mavlink/mavlink_main.cpp

@ -219,7 +219,6 @@ Mavlink::Mavlink() : @@ -219,7 +219,6 @@ Mavlink::Mavlink() :
_logbuffer(5, sizeof(mavlink_log_s)),
_total_counter(0),
_receive_thread{},
_verbose(false),
_forwarding_on(false),
_ftp_on(false),
_uart_fd(-1),
@ -499,32 +498,6 @@ Mavlink::get_status_all_instances() @@ -499,32 +498,6 @@ Mavlink::get_status_all_instances()
return (iterations == 0);
}
void
Mavlink::set_verbose(bool v)
{
_verbose = v;
}
int
Mavlink::set_verbose_all_instances(bool enabled)
{
Mavlink *inst = ::_mavlink_instances;
unsigned iterations = 0;
while (inst != nullptr) {
inst->set_verbose(enabled);
/* move on */
inst = inst->next;
iterations++;
}
/* return an error if there are no instances */
return (iterations == 0);
}
bool
Mavlink::instance_exists(const char *device_name, Mavlink *self)
{
@ -1287,6 +1260,7 @@ void @@ -1287,6 +1260,7 @@ void
Mavlink::send_statustext_critical(const char *string)
{
mavlink_log_critical(&_mavlink_log_pub, string);
PX4_ERR(string);
}
void
@ -1787,7 +1761,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1787,7 +1761,7 @@ Mavlink::task_main(int argc, char *argv[])
int temp_int_arg;
#endif
while ((ch = px4_getopt(argc, argv, "b:r:d:u:o:m:t:fvwx", &myoptind, &myoptarg)) != EOF) {
while ((ch = px4_getopt(argc, argv, "b:r:d:u:o:m:t:fwx", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'b':
_baudrate = strtoul(myoptarg, nullptr, 10);
@ -1901,10 +1875,6 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1901,10 +1875,6 @@ Mavlink::task_main(int argc, char *argv[])
_forwarding_on = true;
break;
case 'v':
_verbose = true;
break;
case 'w':
_wait_to_transmit = true;
break;
@ -2802,11 +2772,9 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50 @@ -2802,11 +2772,9 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50
PRINT_MODULE_USAGE_PARAM_STRING('m', "normal", "custom|camera|onboard|osd|magic|config|iridium",
"Mode: sets default streams and rates", true);
PRINT_MODULE_USAGE_PARAM_FLAG('f', "Enable message forwarding to other Mavlink instances", true);
PRINT_MODULE_USAGE_PARAM_FLAG('v', "Verbose output", true);
PRINT_MODULE_USAGE_PARAM_FLAG('w', "Wait to send, until first message received", true);
PRINT_MODULE_USAGE_PARAM_FLAG('x', "Enable FTP", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("verbose", "Set verbose mode for all running instances");
PRINT_MODULE_USAGE_ARG("on|off", "Enable/disable", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("stop-all", "Stop all instances");
@ -2847,15 +2815,6 @@ int mavlink_main(int argc, char *argv[]) @@ -2847,15 +2815,6 @@ int mavlink_main(int argc, char *argv[])
} else if (!strcmp(argv[1], "status")) {
return Mavlink::get_status_all_instances();
} else if (!strcmp(argv[1], "verbose")) {
bool on = true;
if (argc > 2 && !strcmp(argv[2], "off")) {
on = false;
}
return Mavlink::set_verbose_all_instances(on);
} else if (!strcmp(argv[1], "stream")) {
return Mavlink::stream_command(argc, argv);

18
src/modules/mavlink/mavlink_main.h

@ -134,14 +134,6 @@ public: @@ -134,14 +134,6 @@ public:
static int get_status_all_instances();
/**
* Set all instances to verbose mode
*
* This is primarily intended for analysis and
* not intended for normal operation
*/
static int set_verbose_all_instances(bool enabled);
static bool instance_exists(const char *device_name, Mavlink *self);
static void forward_message(const mavlink_message_t *msg, Mavlink *self);
@ -273,13 +265,6 @@ public: @@ -273,13 +265,6 @@ public:
*/
void set_protocol(Protocol p) { _protocol = p; }
/**
* Set verbose mode
*/
void set_verbose(bool v);
bool get_verbose() const { return _verbose; }
/**
* Get the manual input generation mode
*
@ -449,8 +434,6 @@ public: @@ -449,8 +434,6 @@ 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; } }
@ -524,7 +507,6 @@ private: @@ -524,7 +507,6 @@ private:
pthread_t _receive_thread;
bool _verbose;
bool _forwarding_on;
bool _ftp_on;
#ifndef __PX4_QURT

8
src/modules/mavlink/mavlink_messages.cpp

@ -469,17 +469,13 @@ protected: @@ -469,17 +469,13 @@ protected:
if (_cmd_sub->update_if_changed(&cmd)) {
if (!cmd.from_external) {
if (_mavlink->verbose()) {
PX4_INFO("sending command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
}
PX4_DEBUG("sending command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
MavlinkCommandSender::instance().handle_vehicle_command(cmd, _mavlink->get_channel());
sent = true;
} else {
if (_mavlink->verbose()) {
PX4_INFO("not forwarding command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
}
PX4_DEBUG("not forwarding command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
}
}

136
src/modules/mavlink/mavlink_mission.cpp

@ -68,7 +68,6 @@ uint16_t MavlinkMissionManager::_geofence_update_counter = 0; @@ -68,7 +68,6 @@ uint16_t MavlinkMissionManager::_geofence_update_counter = 0;
(_msg.target_component == MAV_COMP_ID_ALL)))
MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
_verbose(mavlink->verbose()),
_mavlink(mavlink)
{
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
@ -194,7 +193,6 @@ MavlinkMissionManager::update_geofence_count(unsigned count) @@ -194,7 +193,6 @@ MavlinkMissionManager::update_geofence_count(unsigned count)
_count[MAV_MISSION_TYPE_FENCE] = count;
} else {
PX4_ERR("WPM: can't save mission state");
if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) {
_mavlink->send_statustext_critical("Mission storage: Unable to write to microSD");
@ -220,7 +218,6 @@ MavlinkMissionManager::update_safepoint_count(unsigned count) @@ -220,7 +218,6 @@ MavlinkMissionManager::update_safepoint_count(unsigned count)
_count[MAV_MISSION_TYPE_RALLY] = count;
} else {
PX4_ERR("WPM: can't save mission state");
if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) {
_mavlink->send_statustext_critical("Mission storage: Unable to write to microSD");
@ -244,7 +241,7 @@ MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t t @@ -244,7 +241,7 @@ MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t t
mavlink_msg_mission_ack_send_struct(_mavlink->get_channel(), &wpa);
if (_verbose) { PX4_INFO("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); }
PX4_DEBUG("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system);
}
@ -264,7 +261,7 @@ MavlinkMissionManager::send_mission_current(uint16_t seq) @@ -264,7 +261,7 @@ MavlinkMissionManager::send_mission_current(uint16_t seq)
/* don't broadcast if no WPs */
} else {
if (_verbose) { PX4_ERR("WPM: Send MISSION_CURRENT ERROR: seq %u out of bounds", seq); }
PX4_DEBUG("WPM: Send MISSION_CURRENT ERROR: seq %u out of bounds", seq);
_mavlink->send_statustext_critical("ERROR: wp index out of bounds");
}
@ -285,7 +282,7 @@ MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_ @@ -285,7 +282,7 @@ MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_
mavlink_msg_mission_count_send_struct(_mavlink->get_channel(), &wpc);
if (_verbose) { PX4_INFO("WPM: Send MISSION_COUNT %u to ID %u, mission type=%i", wpc.count, wpc.target_system, mission_type); }
PX4_DEBUG("WPM: Send MISSION_COUNT %u to ID %u, mission type=%i", wpc.count, wpc.target_system, mission_type);
}
@ -356,9 +353,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t @@ -356,9 +353,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
mavlink_msg_mission_item_int_send_struct(_mavlink->get_channel(), &wp);
if (_verbose) {
PX4_INFO("WPM: Send MISSION_ITEM_INT seq %u to ID %u", wp.seq, wp.target_system);
}
PX4_DEBUG("WPM: Send MISSION_ITEM_INT seq %u to ID %u", wp.seq, wp.target_system);
} else {
mavlink_mission_item_t wp;
@ -371,9 +366,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t @@ -371,9 +366,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
mavlink_msg_mission_item_send_struct(_mavlink->get_channel(), &wp);
if (_verbose) {
PX4_INFO("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system);
}
PX4_DEBUG("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system);
}
} else {
@ -383,7 +376,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t @@ -383,7 +376,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t
_mavlink->send_statustext_critical("Mission storage: Unable to read from microSD");
}
if (_verbose) { PX4_ERR("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); }
PX4_DEBUG("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id);
}
}
@ -423,9 +416,7 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 @@ -423,9 +416,7 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1
wpr.mission_type = _mission_type;
mavlink_msg_mission_request_int_send_struct(_mavlink->get_channel(), &wpr);
if (_verbose) {
PX4_INFO("WPM: Send MISSION_REQUEST_INT seq %u to ID %u", wpr.seq, wpr.target_system);
}
PX4_DEBUG("WPM: Send MISSION_REQUEST_INT seq %u to ID %u", wpr.seq, wpr.target_system);
} else {
@ -437,15 +428,13 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 @@ -437,15 +428,13 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1
mavlink_msg_mission_request_send_struct(_mavlink->get_channel(), &wpr);
if (_verbose) {
PX4_INFO("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system);
}
PX4_DEBUG("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system);
}
} else {
_mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity");
if (_verbose) { PX4_ERR("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq); }
PX4_DEBUG("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq);
}
}
@ -459,7 +448,7 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq) @@ -459,7 +448,7 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
mavlink_msg_mission_item_reached_send_struct(_mavlink->get_channel(), &wp_reached);
if (_verbose) { PX4_INFO("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq); }
PX4_DEBUG("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq);
}
@ -476,7 +465,7 @@ MavlinkMissionManager::send(const hrt_abstime now) @@ -476,7 +465,7 @@ MavlinkMissionManager::send(const hrt_abstime now)
if (_current_seq != mission_result.seq_current) {
_current_seq = mission_result.seq_current;
if (_verbose) { PX4_INFO("WPM: got mission result, new current_seq: %u", _current_seq); }
PX4_DEBUG("WPM: got mission result, new current_seq: %u", _current_seq);
}
if (_last_reached != mission_result.seq_reached) {
@ -487,7 +476,7 @@ MavlinkMissionManager::send(const hrt_abstime now) @@ -487,7 +476,7 @@ MavlinkMissionManager::send(const hrt_abstime now)
send_mission_item_reached((uint16_t)mission_result.seq_reached);
}
if (_verbose) { PX4_INFO("WPM: got mission result, new seq_reached: %d", _last_reached); }
PX4_DEBUG("WPM: got mission result, new seq_reached: %d", _last_reached);
}
send_mission_current(_current_seq);
@ -526,7 +515,7 @@ MavlinkMissionManager::send(const hrt_abstime now) @@ -526,7 +515,7 @@ MavlinkMissionManager::send(const hrt_abstime now)
} else {
/* try to send item again after timeout */
if (_verbose) { warnx("WPM: item re-send timeout"); }
PX4_DEBUG("WPM: item re-send timeout");
send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq - 1);
}
@ -536,7 +525,7 @@ MavlinkMissionManager::send(const hrt_abstime now) @@ -536,7 +525,7 @@ MavlinkMissionManager::send(const hrt_abstime now)
_mavlink->send_statustext_critical("Operation timeout");
if (_verbose) { PX4_INFO("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state); }
PX4_DEBUG("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state);
switch_to_idle_state();
@ -609,12 +598,12 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) @@ -609,12 +598,12 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
_time_last_recv = hrt_absolute_time();
if (_transfer_seq == current_item_count()) {
if (_verbose) { PX4_INFO("WPM: MISSION_ACK OK all items sent, switch to state IDLE"); }
PX4_DEBUG("WPM: MISSION_ACK OK all items sent, switch to state IDLE");
} else {
_mavlink->send_statustext_critical("WPM: ERR: not all items sent -> IDLE");
if (_verbose) { PX4_ERR("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway"); }
PX4_DEBUG("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway");
}
switch_to_idle_state();
@ -633,9 +622,7 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) @@ -633,9 +622,7 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
} else {
_mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch");
if (_verbose) {
PX4_INFO("WPM: MISSION_ACK ERR: ID mismatch");
}
PX4_DEBUG("WPM: MISSION_ACK ERR: ID mismatch");
}
}
}
@ -653,22 +640,22 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg) @@ -653,22 +640,22 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg)
if (wpc.seq < _count[MAV_MISSION_TYPE_MISSION]) {
if (update_active_mission(_dataman_id, _count[MAV_MISSION_TYPE_MISSION], wpc.seq) == PX4_OK) {
if (_verbose) { PX4_INFO("WPM: MISSION_SET_CURRENT seq=%d OK", wpc.seq); }
PX4_DEBUG("WPM: MISSION_SET_CURRENT seq=%d OK", wpc.seq);
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq); }
PX4_DEBUG("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq);
_mavlink->send_statustext_critical("WPM: WP CURR CMD: Error setting ID");
}
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq); }
PX4_ERR("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq);
_mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list");
}
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_SET_CURRENT ERROR: busy"); }
PX4_DEBUG("WPM: MISSION_SET_CURRENT ERROR: busy");
_mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy");
}
@ -710,20 +697,16 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg) @@ -710,20 +697,16 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg)
_transfer_partner_compid = msg->compid;
if (_transfer_count > 0) {
if (_verbose) {
PX4_INFO("WPM: MISSION_REQUEST_LIST OK, %u mission items to send, mission type=%i", _transfer_count, _mission_type);
}
PX4_DEBUG("WPM: MISSION_REQUEST_LIST OK, %u mission items to send, mission type=%i", _transfer_count, _mission_type);
} else {
if (_verbose) {
PX4_INFO("WPM: MISSION_REQUEST_LIST OK nothing to send, mission is empty, mission type=%i", _mission_type);
}
PX4_DEBUG("WPM: MISSION_REQUEST_LIST OK nothing to send, mission is empty, mission type=%i", _mission_type);
}
send_mission_count(msg->sysid, msg->compid, _transfer_count, _mission_type);
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_REQUEST_LIST ERROR: busy"); }
PX4_DEBUG("WPM: MISSION_REQUEST_LIST ERROR: busy");
_mavlink->send_statustext_critical("IGN REQUEST LIST: Busy");
}
@ -774,22 +757,25 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) @@ -774,22 +757,25 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)
/* _transfer_seq contains sequence of expected request */
if (wpr.seq == _transfer_seq && _transfer_seq < _transfer_count) {
if (_verbose) { PX4_INFO("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u", wpr.seq, msg->sysid); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u", wpr.seq, msg->sysid);
_transfer_seq++;
} else if (wpr.seq == _transfer_seq - 1) {
if (_verbose) { PX4_INFO("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u (again)", wpr.seq, msg->sysid); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) seq %u from ID %u (again)", wpr.seq, msg->sysid);
} else {
if (_transfer_seq > 0 && _transfer_seq < _transfer_count) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i or %i", wpr.seq, msg->sysid, _transfer_seq - 1, _transfer_seq); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i or %i", wpr.seq, msg->sysid,
_transfer_seq - 1, _transfer_seq);
} else if (_transfer_seq <= 0) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid,
_transfer_seq);
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq - 1); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid,
_transfer_seq - 1);
}
switch_to_idle_state();
@ -804,7 +790,8 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) @@ -804,7 +790,8 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)
send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, wpr.seq);
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u out of bound [%u, %u]", wpr.seq, wpr.seq, current_item_count() - 1); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: seq %u out of bound [%u, %u]", wpr.seq, wpr.seq,
current_item_count() - 1);
switch_to_idle_state();
@ -813,13 +800,13 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) @@ -813,13 +800,13 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)
}
} else if (_state == MAVLINK_WPM_STATE_IDLE) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: no transfer"); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: no transfer");
// Silently ignore this as some OSDs have buggy mission protocol implementations
//_mavlink->send_statustext_critical("IGN MISSION_ITEM_REQUEST(_INT): No active transfer");
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: busy (state %d).", _state);
_mavlink->send_statustext_critical("WPM: REJ. CMD: Busy");
}
@ -827,7 +814,7 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg) @@ -827,7 +814,7 @@ MavlinkMissionManager::handle_mission_request_both(const mavlink_message_t *msg)
} else {
_mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch");
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: rejected, partner ID mismatch"); }
PX4_DEBUG("WPM: MISSION_ITEM_REQUEST(_INT) ERROR: rejected, partner ID mismatch");
}
}
}
@ -852,7 +839,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) @@ -852,7 +839,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
_mission_type = (MAV_MISSION_TYPE)wpc.mission_type;
if (wpc.count > current_max_item_count()) {
if (_verbose) { PX4_ERR("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, current_max_item_count()); }
PX4_DEBUG("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, current_max_item_count());
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_NO_SPACE);
_transfer_in_progress = false;
@ -860,7 +847,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) @@ -860,7 +847,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
}
if (wpc.count == 0) {
if (_verbose) { PX4_INFO("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE"); }
PX4_DEBUG("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE");
switch (_mission_type) {
case MAV_MISSION_TYPE_MISSION:
@ -886,7 +873,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) @@ -886,7 +873,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
return;
}
if (_verbose) { PX4_INFO("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); }
PX4_DEBUG("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid);
_state = MAVLINK_WPM_STATE_GETLIST;
_transfer_seq = 0;
@ -899,7 +886,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) @@ -899,7 +886,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
if (_mission_type == MAV_MISSION_TYPE_FENCE) {
// We're about to write new geofence items, so take the lock. It will be released when
// switching back to idle
if (_verbose) { PX4_INFO("locking fence dataman items"); }
PX4_DEBUG("locking fence dataman items");
int ret = dm_lock(DM_KEY_FENCE_POINTS);
@ -916,17 +903,17 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) @@ -916,17 +903,17 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
if (_transfer_seq == 0) {
/* looks like our MISSION_REQUEST was lost, try again */
if (_verbose) { PX4_INFO("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid); }
PX4_DEBUG("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid);
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); }
PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq);
_mavlink->send_statustext_critical("WPM: REJ. CMD: Busy");
return;
}
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_COUNT ERROR: busy, state %i", _state); }
PX4_DEBUG("WPM: MISSION_COUNT ERROR: busy, state %i", _state);
_mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy");
return;
@ -945,7 +932,7 @@ MavlinkMissionManager::switch_to_idle_state() @@ -945,7 +932,7 @@ MavlinkMissionManager::switch_to_idle_state()
dm_unlock(DM_KEY_FENCE_POINTS);
_geofence_locked = false;
if (_verbose) { PX4_INFO("unlocking geofence"); }
PX4_DEBUG("unlocking geofence");
}
_state = MAVLINK_WPM_STATE_IDLE;
@ -995,20 +982,20 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) @@ -995,20 +982,20 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
_time_last_recv = hrt_absolute_time();
if (wp.seq != _transfer_seq) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _transfer_seq); }
PX4_DEBUG("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _transfer_seq);
/* don't send request here, it will be performed in eventloop after timeout */
return;
}
} else if (_state == MAVLINK_WPM_STATE_IDLE) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM ERROR: no transfer"); }
PX4_DEBUG("WPM: MISSION_ITEM ERROR: no transfer");
_mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer");
return;
} else {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM ERROR: busy, state %i", _state); }
PX4_DEBUG("WPM: MISSION_ITEM ERROR: busy, state %i", _state);
_mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy");
return;
@ -1019,7 +1006,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) @@ -1019,7 +1006,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
int ret = parse_mavlink_mission_item(&wp, &mission_item);
if (ret != PX4_OK) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); }
PX4_DEBUG("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq);
_mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy");
@ -1108,7 +1095,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) @@ -1108,7 +1095,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
}
if (write_failed || check_failed) {
if (_verbose) { PX4_ERR("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id); }
PX4_DEBUG("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id);
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
@ -1126,13 +1113,14 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg) @@ -1126,13 +1113,14 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
_transfer_current_seq = wp.seq;
}
if (_verbose) { PX4_INFO("WPM: MISSION_ITEM seq %u received", wp.seq); }
PX4_DEBUG("WPM: MISSION_ITEM seq %u received", wp.seq);
_transfer_seq = wp.seq + 1;
if (_transfer_seq == _transfer_count) {
/* got all new mission items successfully */
if (_verbose) { PX4_INFO("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE", _transfer_count, _transfer_current_seq); }
PX4_DEBUG("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE",
_transfer_count, _transfer_current_seq);
ret = 0;
@ -1215,7 +1203,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg) @@ -1215,7 +1203,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)
}
if (ret == PX4_OK) {
if (_verbose) { PX4_INFO("WPM: CLEAR_ALL OK (mission_type=%i)", _mission_type); }
PX4_DEBUG("WPM: CLEAR_ALL OK (mission_type=%i)", _mission_type);
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED);
@ -1226,7 +1214,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg) @@ -1226,7 +1214,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)
} else {
_mavlink->send_statustext_critical("WPM: IGN CLEAR CMD: Busy");
if (_verbose) { PX4_ERR("WPM: CLEAR_ALL IGNORED: busy"); }
PX4_DEBUG("WPM: CLEAR_ALL IGNORED: busy");
}
}
}
@ -1363,9 +1351,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * @@ -1363,9 +1351,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
default:
mission_item->nav_cmd = NAV_CMD_INVALID;
if (_verbose) {
PX4_ERR("Unsupported command %d", mavlink_mission_item->command);
}
PX4_DEBUG("Unsupported command %d", mavlink_mission_item->command);
return MAV_MISSION_UNSUPPORTED;
}
@ -1429,9 +1415,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * @@ -1429,9 +1415,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
default:
mission_item->nav_cmd = NAV_CMD_INVALID;
if (_verbose) {
PX4_ERR("Unsupported command %d", mavlink_mission_item->command);
}
PX4_DEBUG("Unsupported command %d", mavlink_mission_item->command);
return MAV_MISSION_UNSUPPORTED;
}
@ -1439,9 +1423,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * @@ -1439,9 +1423,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
mission_item->frame = MAV_FRAME_MISSION;
} else {
if (_verbose) {
PX4_ERR("Unsupported frame %d", mavlink_mission_item->frame);
}
PX4_DEBUG("Unsupported frame %d", mavlink_mission_item->frame);
return MAV_MISSION_UNSUPPORTED_FRAME;
}
@ -1610,7 +1592,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * @@ -1610,7 +1592,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
void MavlinkMissionManager::check_active_mission()
{
if (!(_my_dataman_id == _dataman_id)) {
if (_verbose) { PX4_INFO("WPM: New mission detected (possibly over different Mavlink instance) Updating"); }
PX4_DEBUG("WPM: New mission detected (possibly over different Mavlink instance) Updating");
_my_dataman_id = _dataman_id;
send_mission_count(_transfer_partner_sysid, _transfer_partner_compid, _count[MAV_MISSION_TYPE_MISSION],

4
src/modules/mavlink/mavlink_mission.h

@ -87,8 +87,6 @@ public: @@ -87,8 +87,6 @@ public:
void handle_message(const mavlink_message_t *msg);
void set_verbose(bool v) { _verbose = v; }
void check_active_mission(void);
private:
@ -135,8 +133,6 @@ private: @@ -135,8 +133,6 @@ private:
MavlinkRateLimiter _slow_rate_limiter{100 * 1000}; ///< Rate limit sending of the current WP sequence to 10 Hz
bool _verbose;
Mavlink *_mavlink;
static constexpr unsigned int FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT =

10
src/modules/mavlink/mavlink_receiver.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -2368,9 +2368,6 @@ MavlinkReceiver::receive_thread(void *arg) @@ -2368,9 +2368,6 @@ MavlinkReceiver::receive_thread(void *arg)
ssize_t nread = 0;
hrt_abstime last_send_update = 0;
bool verbose = _mavlink->get_verbose();
_mission_manager.set_verbose(verbose);
while (!_mavlink->_task_should_exit) {
if (poll(&fds[0], 1, timeout) > 0) {
if (_mavlink->get_protocol() == SERIAL) {
@ -2475,11 +2472,6 @@ MavlinkReceiver::receive_thread(void *arg) @@ -2475,11 +2472,6 @@ MavlinkReceiver::receive_thread(void *arg)
_mavlink_log_handler.send(t);
last_send_update = t;
if (verbose != _mavlink->get_verbose()) {
verbose = !verbose;
_mission_manager.set_verbose(verbose);
}
}
}

Loading…
Cancel
Save