Browse Source

Copter: fixed a problem with initial parameter fetch

if the GCS connects before the motors have been allocated then it will
get an incorrect parameter count from the MAVLink param protocol. We
need to prevent the PARAM_REQUEST_LIST message from being replied to
until motors are allocated which is done as part of init_ardupilot
master
Andrew Tridgell 8 years ago committed by Randy Mackay
parent
commit
7efca1881c
  1. 7
      ArduCopter/GCS_Mavlink.cpp

7
ArduCopter/GCS_Mavlink.cpp

@ -848,6 +848,13 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: // MAV ID: 21 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: // MAV ID: 21
{ {
// if we have not yet initialised (including allocating the motors
// object) we drop this request. That prevents the GCS from getting
// a confusing parameter count during bootup
if (!copter.ap.initialised) {
break;
}
// mark the firmware version in the tlog // mark the firmware version in the tlog
send_text(MAV_SEVERITY_INFO, FIRMWARE_STRING); send_text(MAV_SEVERITY_INFO, FIRMWARE_STRING);

Loading…
Cancel
Save