mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
SITL: fixed coverity 125055
This commit is contained in:
parent
ed4e8b635a
commit
785ad0614a
@ -80,18 +80,22 @@ bool Aircraft::parse_home(const char *home_str, Location &loc, float &yaw_degree
|
|||||||
}
|
}
|
||||||
char *lat_s = strtok_r(s, ",", &saveptr);
|
char *lat_s = strtok_r(s, ",", &saveptr);
|
||||||
if (!lat_s) {
|
if (!lat_s) {
|
||||||
|
free(s);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
char *lon_s = strtok_r(NULL, ",", &saveptr);
|
char *lon_s = strtok_r(NULL, ",", &saveptr);
|
||||||
if (!lon_s) {
|
if (!lon_s) {
|
||||||
|
free(s);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
char *alt_s = strtok_r(NULL, ",", &saveptr);
|
char *alt_s = strtok_r(NULL, ",", &saveptr);
|
||||||
if (!alt_s) {
|
if (!alt_s) {
|
||||||
|
free(s);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
char *yaw_s = strtok_r(NULL, ",", &saveptr);
|
char *yaw_s = strtok_r(NULL, ",", &saveptr);
|
||||||
if (!yaw_s) {
|
if (!yaw_s) {
|
||||||
|
free(s);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user