Skip to content

Commit 9257685

Browse files
committed
rename AHRS get_roll etc accessors to include _rad
1 parent c578a18 commit 9257685

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

47 files changed

+106
-103
lines changed

ArduCopter/land_detector.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ void Copter::update_land_detector()
7474

7575
// check if landing
7676
const bool landing = flightmode->is_landing();
77-
bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll()) < M_PI/2.0f)
77+
bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll_rad()) < M_PI/2.0f)
7878
#if MODE_AUTOROTATE_ENABLED == ENABLED
7979
|| (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll())
8080
#endif

ArduPlane/ArduPlane.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -939,8 +939,8 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
939939
return;
940940
}
941941
#endif
942-
pitch = ahrs.get_pitch();
943-
roll = ahrs.get_roll();
942+
pitch = ahrs.get_pitch_rad();
943+
roll = ahrs.get_roll_rad();
944944
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for PTCH_TRIM_DEG
945945
pitch -= g.pitch_trim * DEG_TO_RAD;
946946
}

ArduPlane/GCS_Mavlink.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -129,9 +129,9 @@ void GCS_MAVLINK_Plane::send_attitude() const
129129
{
130130
const AP_AHRS &ahrs = AP::ahrs();
131131

132-
float r = ahrs.get_roll();
133-
float p = ahrs.get_pitch();
134-
float y = ahrs.get_yaw();
132+
float r = ahrs.get_roll_rad();
133+
float p = ahrs.get_pitch_rad();
134+
float y = ahrs.get_yaw_rad();
135135

136136
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH))) {
137137
p -= radians(plane.g.pitch_trim);

ArduPlane/commands_logic.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1077,7 +1077,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
10771077
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));
10781078

10791079
// breakout when within 5 degrees of the opposite direction
1080-
if (fabsF(wrap_PI(ahrs.get_yaw() - breakout_direction_rad)) < radians(5.0f)) {
1080+
if (fabsF(wrap_PI(ahrs.get_yaw_rad() - breakout_direction_rad)) < radians(5.0f)) {
10811081
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
10821082
vtol_approach_s.approach_stage = APPROACH_LINE;
10831083
set_next_WP(cmd.content.location);

ArduPlane/mode_cruise.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ void ModeCruise::navigate()
6161

6262
// check if we are moving in the direction of the front of the vehicle
6363
const int32_t ground_course_cd = plane.gps.ground_course_cd();
64-
const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.get_yaw())) < M_PI_2;
64+
const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.get_yaw_rad())) < M_PI_2;
6565

6666
if (!locked_heading &&
6767
plane.channel_roll->get_control_in() == 0 &&

ArduPlane/mode_guided.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ void ModeGuided::update()
5252

5353
float error = 0.0f;
5454
if (plane.guided_state.target_heading_type == GUIDED_HEADING_HEADING) {
55-
error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().get_yaw());
55+
error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().get_yaw_rad());
5656
} else {
5757
Vector2f groundspeed = AP::ahrs().groundspeed_vector();
5858
error = wrap_PI(plane.guided_state.target_heading - atan2f(-groundspeed.y, -groundspeed.x) + M_PI);

ArduPlane/mode_takeoff.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ void ModeTakeoff::update()
8181
const float dist = target_dist;
8282
if (!takeoff_mode_setup) {
8383
const uint16_t altitude = plane.relative_ground_altitude(false,true);
84-
const float direction = degrees(ahrs.get_yaw());
84+
const float direction = degrees(ahrs.get_yaw_rad());
8585
// see if we will skip takeoff as already flying
8686
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
8787
if (altitude >= alt) {

ArduPlane/quadplane.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2667,7 +2667,7 @@ void QuadPlane::vtol_position_controller(void)
26672667
target_speed_xy_cms = diff_wp_norm * target_speed * 100;
26682668
target_accel_cms = diff_wp_norm * (-target_accel*100);
26692669
target_yaw_deg = degrees(diff_wp_norm.angle());
2670-
const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.get_yaw()));
2670+
const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.get_yaw_rad()));
26712671
bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60);
26722672
if (overshoot && !poscontrol.overshoot) {
26732673
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
@@ -3116,7 +3116,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
31163116
*/
31173117
float QuadPlane::get_scaled_wp_speed(float target_bearing_deg) const
31183118
{
3119-
const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.get_yaw()) - target_bearing_deg));
3119+
const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.get_yaw_rad()) - target_bearing_deg));
31203120
const float wp_speed = wp_nav->get_default_speed_xy() * 0.01;
31213121
if (yaw_difference > 20) {
31223122
// this gives a factor of 2x reduction in max speed when

ArduSub/mode_guided.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -385,7 +385,7 @@ void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms)
385385
// helper function to set yaw state and targets
386386
void ModeGuided::guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
387387
{
388-
float current_yaw = wrap_2PI(AP::ahrs().get_yaw());
388+
float current_yaw = wrap_2PI(AP::ahrs().get_yaw_rad());
389389
float euler_yaw_angle;
390390
float yaw_error;
391391

ArduSub/turn_counter.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,11 +8,11 @@ void Sub::update_turn_counter()
88
// Determine state
99
// 0: 0-90 deg, 1: 90-180 deg, 2: -180--90 deg, 3: -90--0 deg
1010
uint8_t turn_state;
11-
if (ahrs.get_yaw() >= 0.0f && ahrs.get_yaw() < radians(90)) {
11+
if (ahrs.get_yaw_rad() >= 0.0f && ahrs.get_yaw_rad() < radians(90)) {
1212
turn_state = 0;
13-
} else if (ahrs.get_yaw() > radians(90)) {
13+
} else if (ahrs.get_yaw_rad() > radians(90)) {
1414
turn_state = 1;
15-
} else if (ahrs.get_yaw() < -radians(90)) {
15+
} else if (ahrs.get_yaw_rad() < -radians(90)) {
1616
turn_state = 2;
1717
} else {
1818
turn_state = 3;

Blimp/Blimp.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -243,7 +243,7 @@ void Blimp::read_AHRS(void)
243243
pos_ned.x,
244244
pos_ned.y,
245245
pos_ned.z,
246-
blimp.ahrs.get_yaw());
246+
blimp.ahrs.get_yaw_rad());
247247
#endif
248248
}
249249

Blimp/Loiter.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ void Loiter::run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled
3434
scaler_xz, scaler_yyaw, scaler_xz_n, scaler_yyaw_n);
3535
#endif
3636

37-
float yaw_ef = blimp.ahrs.get_yaw();
37+
float yaw_ef = blimp.ahrs.get_yaw_rad();
3838
Vector3f err_xyz = target_pos - blimp.pos_ned;
3939
float err_yaw = wrap_PI(target_yaw - yaw_ef);
4040

@@ -96,7 +96,7 @@ void Loiter::run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled
9696
blimp.pid_vel_z.set_integrator(0);
9797
blimp.pid_vel_yaw.set_integrator(0);
9898
target_pos = blimp.pos_ned;
99-
target_yaw = blimp.ahrs.get_yaw();
99+
target_yaw = blimp.ahrs.get_yaw_rad();
100100
}
101101

102102
if (zero.x) {

Blimp/mode_loiter.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
bool ModeLoiter::init(bool ignore_checks)
1010
{
1111
target_pos = blimp.pos_ned;
12-
target_yaw = blimp.ahrs.get_yaw();
12+
target_yaw = blimp.ahrs.get_yaw_rad();
1313

1414
return true;
1515
}
@@ -41,7 +41,7 @@ void ModeLoiter::run()
4141
if (fabsf(target_pos.z-blimp.pos_ned.z) < (g.max_pos_z*POS_LAG)) {
4242
target_pos.z += pilot.z;
4343
}
44-
if (fabsf(wrap_PI(target_yaw-ahrs.get_yaw())) < (g.max_pos_yaw*POS_LAG)) {
44+
if (fabsf(wrap_PI(target_yaw-ahrs.get_yaw_rad())) < (g.max_pos_yaw*POS_LAG)) {
4545
target_yaw = wrap_PI(target_yaw + pilot_yaw);
4646
}
4747

Rover/crash_check.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ void Rover::crash_check()
2020
}
2121

2222
// Crashed if pitch/roll > crash_angle
23-
if ((g2.crash_angle != 0) && ((fabsf(ahrs.get_pitch()) > radians(g2.crash_angle)) || (fabsf(ahrs.get_roll()) > radians(g2.crash_angle)))) {
23+
if ((g2.crash_angle != 0) && ((fabsf(ahrs.get_pitch_rad()) > radians(g2.crash_angle)) || (fabsf(ahrs.get_roll_rad()) > radians(g2.crash_angle)))) {
2424
crashed = true;
2525
}
2626

Rover/mode.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -291,7 +291,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
291291
#if AP_AVOIDANCE_ENABLED
292292
// apply object avoidance to desired speed using half vehicle's maximum deceleration
293293
if (avoidance_enabled) {
294-
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw(), target_speed, rover.G_Dt);
294+
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw_rad(), target_speed, rover.G_Dt);
295295
if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {
296296
// we are a sailboat trying to avoid fence, try a tack
297297
if (rover.control_mode != &rover.mode_acro) {

Rover/mode_circle.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ bool ModeCircle::_enter()
8282

8383
config.dir = (direction == 1) ? Direction::CCW : Direction::CW;
8484
config.speed = is_positive(speed) ? speed : g2.wp_nav.get_default_speed();
85-
target.yaw_rad = AP::ahrs().get_yaw();
85+
target.yaw_rad = AP::ahrs().get_yaw_rad();
8686
target.speed = 0;
8787

8888
// check speed around circle does not lead to excessive lateral acceleration
@@ -116,7 +116,7 @@ void ModeCircle::init_target_yaw_rad()
116116
// if no position estimate use vehicle yaw
117117
Vector2f curr_pos_NE;
118118
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {
119-
target.yaw_rad = AP::ahrs().get_yaw();
119+
target.yaw_rad = AP::ahrs().get_yaw_rad();
120120
return;
121121
}
122122

@@ -126,7 +126,7 @@ void ModeCircle::init_target_yaw_rad()
126126

127127
// if current position is exactly at the center of the circle return vehicle yaw
128128
if (is_zero(dist_m)) {
129-
target.yaw_rad = AP::ahrs().get_yaw();
129+
target.yaw_rad = AP::ahrs().get_yaw_rad();
130130
} else {
131131
target.yaw_rad = center_to_veh.angle();
132132
}

Rover/sailboat.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -319,7 +319,7 @@ float Sailboat::get_VMG() const
319319
return speed;
320320
}
321321

322-
return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.get_yaw())));
322+
return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.get_yaw_rad())));
323323
}
324324

325325
// handle user initiated tack while in acro mode
@@ -330,15 +330,15 @@ void Sailboat::handle_tack_request_acro()
330330
}
331331
// set tacking heading target to the current angle relative to the true wind but on the new tack
332332
currently_tacking = true;
333-
tack_heading_rad = wrap_2PI(rover.ahrs.get_yaw() + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.get_yaw())));
333+
tack_heading_rad = wrap_2PI(rover.ahrs.get_yaw_rad() + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.get_yaw_rad())));
334334

335335
tack_request_ms = AP_HAL::millis();
336336
}
337337

338338
// return target heading in radians when tacking (only used in acro)
339339
float Sailboat::get_tack_heading_rad()
340340
{
341-
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) < radians(SAILBOAT_TACKING_ACCURACY_DEG) ||
341+
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw_rad())) < radians(SAILBOAT_TACKING_ACCURACY_DEG) ||
342342
((AP_HAL::millis() - tack_request_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS)) {
343343
clear_tack();
344344
}
@@ -484,7 +484,7 @@ float Sailboat::calc_heading(float desired_heading_cd)
484484
// if we are tacking we maintain the target heading until the tack completes or times out
485485
if (currently_tacking) {
486486
// check if we have reached target
487-
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
487+
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw_rad())) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
488488
clear_tack();
489489
} else if ((now - auto_tack_start_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS) {
490490
// tack has taken too long

libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,10 @@ void AC_AttitudeControl_Multi_6DoF::rate_controller_run() {
2020
// if 6DoF control, always point directly up
2121
// this stops horizontal drift due to error between target and true attitude
2222
if (lateral_enable) {
23-
roll_deg = degrees(AP::ahrs().get_roll());
23+
roll_deg = degrees(AP::ahrs().get_roll_rad());
2424
}
2525
if (forward_enable) {
26-
pitch_deg = degrees(AP::ahrs().get_pitch());
26+
pitch_deg = degrees(AP::ahrs().get_pitch_rad());
2727
}
2828
_motors.set_roll_pitch(roll_deg,pitch_deg);
2929

libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -460,7 +460,7 @@ void AC_AttitudeControl_Sub::input_euler_angle_roll_pitch_slew_yaw(float euler_r
460460
// Convert from centidegrees on public interface to radians
461461
const float euler_yaw_angle = wrap_PI(radians(euler_yaw_angle_cd * 0.01f));
462462

463-
const float current_yaw = AP::ahrs().get_yaw();
463+
const float current_yaw = AP::ahrs().get_yaw_rad();
464464

465465
// Compute angle error
466466
const float yaw_error = wrap_PI(euler_yaw_angle - current_yaw);
@@ -491,4 +491,4 @@ void AC_AttitudeControl_Sub::set_notch_sample_rate(float sample_rate)
491491
_pid_rate_pitch.set_notch_sample_rate(sample_rate);
492492
_pid_rate_yaw.set_notch_sample_rate(sample_rate);
493493
#endif
494-
}
494+
}

libraries/APM_Control/AP_PitchController.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -273,7 +273,7 @@ float AP_PitchController::get_rate_out(float desired_rate, float scaler)
273273
float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const
274274
{
275275
float rate_offset;
276-
float bank_angle = AP::ahrs().get_roll();
276+
float bank_angle = AP::ahrs().get_roll_rad();
277277

278278
// limit bank angle between +- 80 deg if right way up
279279
if (fabsf(bank_angle) < radians(90)) {
@@ -296,7 +296,7 @@ float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inv
296296
// don't do turn coordination handling when at very high pitch angles
297297
rate_offset = 0;
298298
} else {
299-
rate_offset = cosf(_ahrs.get_pitch())*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
299+
rate_offset = cosf(_ahrs.get_pitch_rad())*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;
300300
}
301301
if (inverted) {
302302
rate_offset = -rate_offset;

libraries/APM_Control/AP_YawController.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
206206
// Calculate yaw rate required to keep up with a constant height coordinated turn
207207
float aspeed;
208208
float rate_offset;
209-
float bank_angle = AP::ahrs().get_roll();
209+
float bank_angle = AP::ahrs().get_roll_rad();
210210
// limit bank angle between +- 80 deg if right way up
211211
if (fabsf(bank_angle) < 1.5707964f) {
212212
bank_angle = constrain_float(bank_angle,-1.3962634f,1.3962634f);

libraries/APM_Control/AR_AttitudeControl.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -613,7 +613,7 @@ float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate
613613
// return a desired turn-rate given a desired heading in radians
614614
float AR_AttitudeControl::get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const
615615
{
616-
const float yaw_error = wrap_PI(heading_rad - AP::ahrs().get_yaw());
616+
const float yaw_error = wrap_PI(heading_rad - AP::ahrs().get_yaw_rad());
617617

618618
// Calculate the desired turn rate (in radians) from the angle error (also in radians)
619619
float desired_rate = _steer_angle_p.get_p(yaw_error);
@@ -884,7 +884,7 @@ float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float
884884
}
885885

886886
// initialise output to feed forward from current pitch angle
887-
const float pitch_rad = AP::ahrs().get_pitch();
887+
const float pitch_rad = AP::ahrs().get_pitch_rad();
888888
float output = sinf(pitch_rad) * _pitch_to_throttle_ff;
889889

890890
// add regular PID control
@@ -940,7 +940,7 @@ float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt)
940940
}
941941
_heel_controller_last_ms = now;
942942

943-
_sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().get_roll()), dt);
943+
_sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().get_roll_rad()), dt);
944944

945945
// get feed-forward
946946
const float ff = _sailboat_heel_pid.get_ff();

libraries/AP_AHRS/AP_AHRS.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -549,9 +549,9 @@ class AP_AHRS {
549549
*/
550550

551551
// roll/pitch/yaw euler angles, all in radians
552-
float get_roll() const { return roll; }
553-
float get_pitch() const { return pitch; }
554-
float get_yaw() const { return yaw; }
552+
float get_roll_rad() const { return roll; }
553+
float get_pitch_rad() const { return pitch; }
554+
float get_yaw_rad() const { return yaw; }
555555

556556
// helper trig value accessors
557557
float cos_roll() const {

libraries/AP_Compass/AP_Compass_Calibration.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -538,7 +538,7 @@ bool Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
538538
field = R * field;
539539

540540
Matrix3f dcm;
541-
dcm.from_euler(AP::ahrs().get_roll(), AP::ahrs().get_pitch(), radians(yaw_deg));
541+
dcm.from_euler(AP::ahrs().get_roll_rad(), AP::ahrs().get_pitch_rad(), radians(yaw_deg));
542542

543543
// Rotate into body frame using provided yaw
544544
field = dcm.transposed() * field;

libraries/AP_Compass/Compass_learn.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ void CompassLearn::update(void)
4343
// no GSF available
4444
return;
4545
}
46-
if (degrees(fabsf(ahrs.get_pitch())) > 50) {
46+
if (degrees(fabsf(ahrs.get_pitch_rad())) > 50) {
4747
// we don't want to be too close to nose up, or yaw gets
4848
// problematic. Tailsitters need to wait till they are in
4949
// forward flight

libraries/AP_DroneCAN/AP_DroneCAN.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1037,7 +1037,7 @@ void AP_DroneCAN::notify_state_send()
10371037
#endif // HAL_BUILD_AP_PERIPH
10381038

10391039
msg.aux_data_type = ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES;
1040-
uint16_t yaw_cd = (uint16_t)(360.0f - degrees(AP::ahrs().get_yaw()))*100.0f;
1040+
uint16_t yaw_cd = (uint16_t)(360.0f - degrees(AP::ahrs().get_yaw_rad()))*100.0f;
10411041
const uint8_t *data = (uint8_t *)&yaw_cd;
10421042
for (uint8_t i=0; i<2; i++) {
10431043
msg.aux_data.data[i] = data[i];

libraries/AP_InertialSensor/AP_InertialSensor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1345,7 +1345,7 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, Vector3f &
13451345
if (view != nullptr) {
13461346
// Use pitch to guess which axis the user is trying to trim
13471347
// 5 deg buffer to favor normal AHRS and avoid floating point funny business
1348-
if (fabsf(view->pitch) < (fabsf(AP::ahrs().get_pitch())+radians(5)) ) {
1348+
if (fabsf(view->pitch) < (fabsf(AP::ahrs().get_pitch_rad())+radians(5)) ) {
13491349
// user is trying to calibrate view
13501350
rotation = view->get_rotation();
13511351
if (!is_zero(view->get_pitch_trim())) {

0 commit comments

Comments
 (0)