mirror of https://github.com/ArduPilot/ardupilot
AP_ExternalAHRS: make get_accel() and get_gyro() bool
This commit is contained in:
parent
77e5446595
commit
c6c0de9889
|
@ -250,16 +250,24 @@ void AP_ExternalAHRS::get_filter_status(nav_filter_status &status) const
|
|||
}
|
||||
}
|
||||
|
||||
Vector3f AP_ExternalAHRS::get_gyro(void)
|
||||
bool AP_ExternalAHRS::get_gyro(Vector3f &gyro)
|
||||
{
|
||||
WITH_SEMAPHORE(state.sem);
|
||||
return state.gyro;
|
||||
if (!has_sensor(AvailableSensor::IMU)) {
|
||||
return false;
|
||||
}
|
||||
gyro = state.gyro;
|
||||
return true;
|
||||
}
|
||||
|
||||
Vector3f AP_ExternalAHRS::get_accel(void)
|
||||
bool AP_ExternalAHRS::get_accel(Vector3f &accel)
|
||||
{
|
||||
WITH_SEMAPHORE(state.sem);
|
||||
return state.accel;
|
||||
if (!has_sensor(AvailableSensor::IMU)) {
|
||||
return false;
|
||||
}
|
||||
accel = state.accel;
|
||||
return true;
|
||||
}
|
||||
|
||||
// send an EKF_STATUS message to GCS
|
||||
|
|
|
@ -115,8 +115,8 @@ public:
|
|||
bool get_speed_down(float &speedD);
|
||||
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;
|
||||
void get_filter_status(nav_filter_status &status) const;
|
||||
Vector3f get_gyro(void);
|
||||
Vector3f get_accel(void);
|
||||
bool get_gyro(Vector3f &gyro);
|
||||
bool get_accel(Vector3f &accel);
|
||||
void send_status_report(class GCS_MAVLINK &link) const;
|
||||
|
||||
// update backend
|
||||
|
|
Loading…
Reference in New Issue