mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'ArduPilot:master' into master
This commit is contained in:
commit
331b58dcb0
|
@ -1,13 +1,14 @@
|
|||
QGC WPL 110
|
||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
||||
1 0 3 84 0.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||
6 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||
11 0 3 85 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
||||
1 0 0 223 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
2 0 3 84 0.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||
7 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
8 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||
11 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||
12 0 3 85 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
||||
|
|
|
@ -1,13 +1,14 @@
|
|||
QGC WPL 110
|
||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
||||
1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||
6 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||
11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
||||
1 0 0 223 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
2 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||
7 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
8 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||
11 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||
12 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
||||
|
|
|
@ -9462,9 +9462,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("Actually, no I'm not - it is an external simulation")
|
||||
continue
|
||||
model = frame_bits.get("model", frame)
|
||||
# the model string for Callisto has crap in it.... we
|
||||
# should really have another entry in the vehicleinfo data
|
||||
# to carry the path to the JSON.
|
||||
defaults = self.model_defaults_filepath(frame)
|
||||
if not isinstance(defaults, list):
|
||||
defaults = [defaults]
|
||||
|
|
|
@ -4200,9 +4200,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
vinfo = vehicleinfo.VehicleInfo()
|
||||
vinfo_options = vinfo.options[self.vehicleinfo_key()]
|
||||
known_broken_frames = {
|
||||
"plane-tailsitter": "does not take off; immediately emits 'AP: Transition VTOL done' while on ground",
|
||||
"plane-ice" : "needs ICE control channel for ignition",
|
||||
"quadplane-ice" : "needs ICE control channel for ignition",
|
||||
"plane-tailsitter": "unstable in hover; unflyable in cruise",
|
||||
"quadplane-can" : "needs CAN periph",
|
||||
"stratoblimp" : "not expected to fly normally",
|
||||
"glider" : "needs balloon lift",
|
||||
|
@ -4219,11 +4217,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.progress("Actually, no I'm not - it is an external simulation")
|
||||
continue
|
||||
model = frame_bits.get("model", frame)
|
||||
# the model string for Callisto has crap in it.... we
|
||||
# should really have another entry in the vehicleinfo data
|
||||
# to carry the path to the JSON.
|
||||
actual_model = model.split(":")[0]
|
||||
defaults = self.model_defaults_filepath(actual_model)
|
||||
defaults = self.model_defaults_filepath(frame)
|
||||
if not isinstance(defaults, list):
|
||||
defaults = [defaults]
|
||||
self.customise_SITL_commandline(
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
ICE_ENABLE 1
|
||||
ICE_RPM_CHAN 1
|
||||
ICE_RPM_THRESH 50
|
||||
SERVO13_FUNCTION 67
|
||||
SERVO14_FUNCTION 69
|
||||
RC11_OPTION 179
|
||||
|
|
|
@ -92,21 +92,33 @@ void AP_Proximity_LD06::get_readings()
|
|||
// Loops through all bytes that were received
|
||||
while (nbytes-- > 0) {
|
||||
|
||||
// Gets and logs the current byte being read
|
||||
const uint8_t c = _uart->read();
|
||||
uint8_t c;
|
||||
if (!_uart->read(c)) {
|
||||
break;
|
||||
}
|
||||
|
||||
// Stores the byte in an array if the byte is a start byte or we have already read a start byte
|
||||
if (c == LD_START_CHAR || _response_data) {
|
||||
|
||||
// Sets to true if a start byte has been read, default false otherwise
|
||||
_response_data = true;
|
||||
|
||||
if (c == LD_START_CHAR || _byte_count) {
|
||||
// Stores the next byte in an array
|
||||
_response[_byte_count] = c;
|
||||
if (_byte_count < START_DATA_LENGTH) {
|
||||
_byte_count++;
|
||||
continue;
|
||||
}
|
||||
|
||||
const uint32_t total_packet_length = _response[START_DATA_LENGTH] + 3;
|
||||
if (total_packet_length > ARRAY_SIZE(_response)) {
|
||||
// invalid packet received; throw away all data and
|
||||
// start again.
|
||||
_byte_count = 0;
|
||||
_uart->discard_input();
|
||||
break;
|
||||
}
|
||||
|
||||
_byte_count++;
|
||||
|
||||
if (_byte_count == _response[START_DATA_LENGTH] + 3) {
|
||||
|
||||
if (_byte_count == total_packet_length) {
|
||||
|
||||
const uint32_t current_ms = AP_HAL::millis();
|
||||
|
||||
// Stores the last distance taken, used to reduce number of readings taken
|
||||
|
@ -121,7 +133,6 @@ void AP_Proximity_LD06::get_readings()
|
|||
|
||||
// Resets the bytes read and whether or not we are reading data to accept a new payload
|
||||
_byte_count = 0;
|
||||
_response_data = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -57,7 +57,6 @@ private:
|
|||
|
||||
// Store and keep track of the bytes being read from the sensor
|
||||
uint8_t _response[MESSAGE_LENGTH_LD06];
|
||||
bool _response_data;
|
||||
uint16_t _byte_count;
|
||||
|
||||
// Store for error-tracking purposes
|
||||
|
|
Loading…
Reference in New Issue