Browse Source

Backport of Fixes mavlink_if0: invalid data rate '(null)' bug

sbg
David Sidrane 10 years ago
parent
commit
28d3729acd
  1. 27
      src/modules/mavlink/mavlink_main.cpp

27
src/modules/mavlink/mavlink_main.cpp

@ -784,6 +784,7 @@ Mavlink::get_free_tx_buf() @@ -784,6 +784,7 @@ Mavlink::get_free_tx_buf()
enable_flow_control(false);
}
}
#endif
return buf_free;
@ -851,6 +852,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg, uint8_t component_ID @@ -851,6 +852,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg, uint8_t component_ID
_last_write_success_time = _last_write_try_time;
count_txbytes(packet_len);
}
#endif
pthread_mutex_unlock(&_send_mutex);
@ -903,6 +905,7 @@ Mavlink::resend_message(mavlink_message_t *msg) @@ -903,6 +905,7 @@ Mavlink::resend_message(mavlink_message_t *msg)
_last_write_success_time = _last_write_try_time;
count_txbytes(packet_len);
}
#endif
pthread_mutex_unlock(&_send_mutex);
@ -954,7 +957,8 @@ Mavlink::send_statustext(unsigned char severity, const char *string) @@ -954,7 +957,8 @@ Mavlink::send_statustext(unsigned char severity, const char *string)
mavlink_logbuffer_write(&_logbuffer, &logmsg);
}
void Mavlink::send_autopilot_capabilites() {
void Mavlink::send_autopilot_capabilites()
{
struct vehicle_status_s status;
MavlinkOrbSubscription *status_sub = this->add_orb_subscription(ORB_ID(vehicle_status));
@ -1287,11 +1291,14 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1287,11 +1291,14 @@ Mavlink::task_main(int argc, char *argv[])
_datarate = 0;
_mode = MAVLINK_MODE_NORMAL;
#ifdef __PX4_NUTTX
/* work around some stupidity in task_create's argv handling */
argc -= 2;
argv += 2;
#endif
/*
* Called via create_task with taskname followed by original argv
* <name> mavlink start
*
* Remove all 3
*/
argc -= 3;
argv += 3;
/* don't exit from getopt loop to leave getopt global variables in consistent state,
* set error flag instead */
@ -1336,6 +1343,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1336,6 +1343,7 @@ Mavlink::task_main(int argc, char *argv[])
} else if (strcmp(myoptarg, "camera") == 0) {
// left in here for compatibility
_mode = MAVLINK_MODE_ONBOARD;
} else if (strcmp(myoptarg, "onboard") == 0) {
_mode = MAVLINK_MODE_ONBOARD;
}
@ -1402,6 +1410,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1402,6 +1410,7 @@ Mavlink::task_main(int argc, char *argv[])
warn("could not open %s", _device_name);
return ERROR;
}
#endif
/* initialize send mutex */
@ -1816,6 +1825,12 @@ Mavlink::stream_command(int argc, char *argv[]) @@ -1816,6 +1825,12 @@ Mavlink::stream_command(int argc, char *argv[])
float rate = -1.0f;
const char *stream_name = nullptr;
/*
* Called via main with original argv
* mavlink start
*
* Remove 2
*/
argc -= 2;
argv += 2;

Loading…
Cancel
Save