AP_AHRS: correct infinite recursion in AP_AHRS_View
This commit is contained in:
parent
29b06d2d4a
commit
1217256898
@ -118,12 +118,12 @@ public:
|
|||||||
return ahrs.get_relative_position_NE_origin(vecNE);
|
return ahrs.get_relative_position_NE_origin(vecNE);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool get_relative_position_D_home(float &posD) const {
|
void get_relative_position_D_home(float &posD) const {
|
||||||
return get_relative_position_D_home(posD);
|
ahrs.get_relative_position_D_home(posD);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool get_relative_position_D_origin(float &posD) const {
|
bool get_relative_position_D_origin(float &posD) const {
|
||||||
return get_relative_position_D_origin(posD);
|
return ahrs.get_relative_position_D_origin(posD);
|
||||||
}
|
}
|
||||||
|
|
||||||
float groundspeed(void) {
|
float groundspeed(void) {
|
||||||
|
Loading…
Reference in New Issue
Block a user