mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Compass: add get_motor_compensation
Remove redundant set_motor_compensation call
This commit is contained in:
parent
987cdaf3e1
commit
e113eb526b
@ -132,14 +132,9 @@ public:
|
|||||||
///
|
///
|
||||||
void set_motor_compensation(const Vector3f &motor_comp_factor);
|
void set_motor_compensation(const Vector3f &motor_comp_factor);
|
||||||
|
|
||||||
/// Set new motor compensation factors as a vector
|
/// get motor compensation factors as a vector
|
||||||
///
|
Vector3f& get_motor_compensation() {
|
||||||
/// @param x multiplied by throttle value and added to the raw mag_x value.
|
return _motor_compensation;
|
||||||
/// @param y multiplied by throttle value and added to the raw mag_y value.
|
|
||||||
/// @param z multiplied by throttle value and added to the raw mag_z value.
|
|
||||||
///
|
|
||||||
void set_motor_compensation(float x, float y, float z) {
|
|
||||||
set_motor_compensation(Vector3f(x, y, z));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Saves the current motor compensation x/y/z values.
|
/// Saves the current motor compensation x/y/z values.
|
||||||
|
Loading…
Reference in New Issue
Block a user