Skip to content

Commit ad6479a

Browse files
committed
Experiment: use radians(0.01f) to convert to radians from cd
1 parent 312bf8d commit ad6479a

22 files changed

+46
-46
lines changed

ArduCopter/mode.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -768,7 +768,7 @@ void Mode::land_run_horizontal_control()
768768
// interpolate for 1m above that
769769
const float attitude_limit_cd = linear_interpolate(700, copter.aparm.angle_max, get_alt_above_ground_cm(),
770770
g2.wp_navalt_min*100U, (g2.wp_navalt_min+1)*100U);
771-
const float thrust_vector_max = sinf(radians(attitude_limit_cd * 0.01f)) * GRAVITY_MSS * 100.0f;
771+
const float thrust_vector_max = sinf(attitude_limit_cd * radians(0.01f)) * GRAVITY_MSS * 100.0f;
772772
const float thrust_vector_mag = thrust_vector.xy().length();
773773
if (thrust_vector_mag > thrust_vector_max) {
774774
float ratio = thrust_vector_max / thrust_vector_mag;

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(ground_course_cd * radians(0.01) - plane.ahrs.get_yaw())) < M_PI_2;
6565

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

ArduPlane/quadplane.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -930,7 +930,7 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
930930
float yaw2roll_scale = roll_limit / yaw_rate_limit;
931931

932932
// Rotate as a function of Euler pitch and swap roll/yaw
933-
float euler_pitch = radians(.01f * plane.nav_pitch_cd);
933+
float euler_pitch = radians(.01f) * plane.nav_pitch_cd;
934934
float spitch = fabsf(sinf(euler_pitch));
935935
float y2r_scale = linear_interpolate(1, yaw2roll_scale, spitch, 0, 1);
936936

@@ -1136,7 +1136,7 @@ void QuadPlane::get_pilot_desired_lean_angles(float &roll_out_cd, float &pitch_o
11361136
}
11371137

11381138
// apply lateral tilt to euler roll conversion
1139-
roll_out_cd = 100 * degrees(atanf(cosf(radians(pitch_out_cd*0.01))*tanf(radians(roll_out_cd*0.01))));
1139+
roll_out_cd = 100 * degrees(atanf(cosf(pitch_out_cd * radians(0.01)) * tanf(roll_out_cd * radians(0.01))));
11401140
}
11411141

11421142
/*

Rover/mode.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -496,7 +496,7 @@ void Mode::calc_steering_from_lateral_acceleration(float lat_accel, bool reverse
496496
void Mode::calc_steering_to_heading(float desired_heading_cd, float rate_max_degs)
497497
{
498498
// call heading controller
499-
const float steering_out = attitude_control.get_steering_out_heading(radians(desired_heading_cd*0.01f),
499+
const float steering_out = attitude_control.get_steering_out_heading(desired_heading_cd * radians(0.01f),
500500
radians(rate_max_degs),
501501
g2.motors.limit.steer_left,
502502
g2.motors.limit.steer_right,

Rover/mode_guided.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ void ModeGuided::update()
8282
}
8383
if (have_attitude_target) {
8484
// run steering and throttle controllers
85-
float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds * 0.01f),
85+
float steering_out = attitude_control.get_steering_out_rate(_desired_yaw_rate_cds * radians(0.01f),
8686
g2.motors.limit.steer_left,
8787
g2.motors.limit.steer_right,
8888
rover.G_Dt);

Rover/sailboat.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -317,7 +317,7 @@ float Sailboat::get_VMG() const
317317
return speed;
318318
}
319319

320-
return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.get_yaw())));
320+
return (speed * cosf(wrap_PI(rover.g2.wp_nav.wp_bearing_cd() * radians(0.01f) - rover.ahrs.get_yaw())));
321321
}
322322

323323
// handle user initiated tack while in acro mode
@@ -384,7 +384,7 @@ bool Sailboat::use_indirect_route(float desired_heading_cd) const
384384
}
385385

386386
// convert desired heading to radians
387-
const float desired_heading_rad = radians(desired_heading_cd * 0.01f);
387+
const float desired_heading_rad = desired_heading_cd * radians(0.01f);
388388

389389
// check if desired heading is in the no go zone, if it is we can't go direct
390390
// pad no go zone, this allows use of heading controller rather than L1 when close to the wind
@@ -404,7 +404,7 @@ float Sailboat::calc_heading(float desired_heading_cd)
404404
const AP_WindVane::Sailboat_Tack current_tack = rover.g2.windvane.get_current_tack();
405405

406406
// convert desired heading to radians
407-
const float desired_heading_rad = radians(desired_heading_cd * 0.01f);
407+
const float desired_heading_rad = desired_heading_cd * radians(0.01f);
408408

409409
// if the desired heading is outside the no go zone there is no need to change it
410410
// this allows use of heading controller rather than L1 when desired

Tools/AP_Periph/adsb.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -103,7 +103,7 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg)
103103
pkt.longitude_deg_1e7 = msg.lon;
104104
pkt.alt_m = msg.altitude * 1e-3;
105105

106-
pkt.heading = radians(msg.heading * 1e-2);
106+
pkt.heading = msg.heading * radians(1e-2);
107107

108108
pkt.velocity[0] = cosf(pkt.heading) * msg.hor_velocity * 1e-2;
109109
pkt.velocity[1] = sinf(pkt.heading) * msg.hor_velocity * 1e-2;

Tools/AP_Periph/can.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -699,7 +699,7 @@ void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRx
699699
if (msg.aux_data.len == 2 && msg.aux_data_type == ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES) {
700700
uint16_t tmp = 0;
701701
memcpy(&tmp, msg.aux_data.data, sizeof(tmp));
702-
yaw_earth = radians((float)tmp * 0.01f);
702+
yaw_earth = (float)tmp * radians(0.01f);
703703
}
704704
vehicle_state = msg.vehicle_state;
705705
last_vehicle_state = AP_HAL::millis();

libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -324,7 +324,7 @@ AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_Mu
324324
void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)
325325
{
326326
// convert from centidegrees on public interface to radians
327-
float yaw_rate_bf_rads = radians(yaw_rate_bf_cds * 0.01f);
327+
float yaw_rate_bf_rads = yaw_rate_bf_cds * radians(0.01f);
328328

329329
// store roll, pitch and passthroughs
330330
// NOTE: this abuses yaw_rate_bf_rads

libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ void AC_AttitudeControl_Multi_6DoF::set_forward_lateral(float &euler_pitch_angle
7474
{
7575
// pitch/forward
7676
if (forward_enable) {
77-
_motors.set_forward(-sinf(radians(euler_pitch_angle_cd * 0.01f)));
77+
_motors.set_forward(-sinf(euler_pitch_angle_cd * radians(0.01f)));
7878
euler_pitch_angle_cd = pitch_offset_deg * 100.0f;
7979
} else {
8080
_motors.set_forward(0.0f);
@@ -84,7 +84,7 @@ void AC_AttitudeControl_Multi_6DoF::set_forward_lateral(float &euler_pitch_angle
8484

8585
// roll/lateral
8686
if (lateral_enable) {
87-
_motors.set_lateral(sinf(radians(euler_roll_angle_cd * 0.01f)));
87+
_motors.set_lateral(sinf(euler_roll_angle_cd * radians(0.01f)));
8888
euler_roll_angle_cd = roll_offset_deg * 100.0f;
8989
} else {
9090
_motors.set_lateral(0.0f);

libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -455,7 +455,7 @@ void AC_AttitudeControl_Sub::parameter_sanity_check()
455455
void AC_AttitudeControl_Sub::input_euler_angle_roll_pitch_slew_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float target_yaw_rate)
456456
{
457457
// Convert from centidegrees on public interface to radians
458-
const float euler_yaw_angle = wrap_PI(radians(euler_yaw_angle_cd * 0.01f));
458+
const float euler_yaw_angle = wrap_PI(euler_yaw_angle_cd * radians(0.01f));
459459

460460
const float current_yaw = AP::ahrs().get_yaw();
461461

libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -61,9 +61,9 @@ void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch)
6161
void AC_AttitudeControl_TS::input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool plane_controls, float body_roll_cd, float euler_pitch_cd, float euler_yaw_rate_cds)
6262
{
6363
// Convert from centidegrees on public interface to radians
64-
float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);
64+
float euler_yaw_rate = euler_yaw_rate_cds * radians(0.01f);
6565
float euler_pitch = radians(constrain_float(euler_pitch_cd * 0.01f, -90.0f, 90.0f));
66-
float body_roll = radians(-body_roll_cd * 0.01f);
66+
float body_roll = -body_roll_cd * radians(0.01f);
6767

6868
const float cpitch = cosf(euler_pitch);
6969
const float spitch = fabsf(sinf(euler_pitch));

libraries/AC_AutoTune/AC_AutoTune_Heli.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -852,43 +852,43 @@ void AC_AutoTune_Heli::dwell_test_run(sweep_info &test_data)
852852
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_angle_cd + trim_angle_cd.x, trim_angle_cd.y, 0.0f);
853853
command_reading = motors->get_roll();
854854
if (test_calc_type == DRB) {
855-
tgt_rate_reading = radians(target_angle_cd * 0.01f);
856-
gyro_reading = radians(((float)ahrs_view->roll_sensor + trim_angle_cd.x - target_angle_cd) * 0.01f);
855+
tgt_rate_reading = target_angle_cd * radians(0.01f);
856+
gyro_reading = ((float)ahrs_view->roll_sensor + trim_angle_cd.x - target_angle_cd) * radians(0.01f);
857857
} else if (test_calc_type == RATE) {
858858
tgt_rate_reading = attitude_control->rate_bf_targets().x;
859859
gyro_reading = ahrs_view->get_gyro().x;
860860
} else {
861-
tgt_rate_reading = radians((float)attitude_control->get_att_target_euler_cd().x * 0.01f);
862-
gyro_reading = radians((float)ahrs_view->roll_sensor * 0.01f);
861+
tgt_rate_reading = (float)attitude_control->get_att_target_euler_cd().x * radians(0.01f);
862+
gyro_reading = (float)ahrs_view->roll_sensor * radians(0.01f);
863863
}
864864
break;
865865
case AxisType::PITCH:
866866
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(trim_angle_cd.x, target_angle_cd + trim_angle_cd.y, 0.0f);
867867
command_reading = motors->get_pitch();
868868
if (test_calc_type == DRB) {
869-
tgt_rate_reading = radians(target_angle_cd * 0.01f);
870-
gyro_reading = radians(((float)ahrs_view->pitch_sensor + trim_angle_cd.y - target_angle_cd) * 0.01f);
869+
tgt_rate_reading = target_angle_cd * radians(0.01f);
870+
gyro_reading = ((float)ahrs_view->pitch_sensor + trim_angle_cd.y - target_angle_cd) * radians(0.01f);
871871
} else if (test_calc_type == RATE) {
872872
tgt_rate_reading = attitude_control->rate_bf_targets().y;
873873
gyro_reading = ahrs_view->get_gyro().y;
874874
} else {
875-
tgt_rate_reading = radians((float)attitude_control->get_att_target_euler_cd().y * 0.01f);
876-
gyro_reading = radians((float)ahrs_view->pitch_sensor * 0.01f);
875+
tgt_rate_reading = (float)attitude_control->get_att_target_euler_cd().y * radians(0.01f);
876+
gyro_reading = (float)ahrs_view->pitch_sensor * radians(0.01f);
877877
}
878878
break;
879879
case AxisType::YAW:
880880
case AxisType::YAW_D:
881881
attitude_control->input_euler_angle_roll_pitch_yaw_cd(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading_cd + target_angle_cd), false);
882882
command_reading = motors->get_yaw();
883883
if (test_calc_type == DRB) {
884-
tgt_rate_reading = radians(target_angle_cd * 0.01f);
885-
gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd - target_angle_cd)) * 0.01f);
884+
tgt_rate_reading = target_angle_cd * radians(0.01f);
885+
gyro_reading = (wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd - target_angle_cd)) * radians(0.01f);
886886
} else if (test_calc_type == RATE) {
887887
tgt_rate_reading = attitude_control->rate_bf_targets().z;
888888
gyro_reading = ahrs_view->get_gyro().z;
889889
} else {
890-
tgt_rate_reading = radians((wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading_cd)) * 0.01f);
891-
gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd)) * 0.01f);
890+
tgt_rate_reading = (wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading_cd)) * radians(0.01f);
891+
gyro_reading = (wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd)) * radians(0.01f);
892892
}
893893
break;
894894
}

libraries/AC_WPNav/AC_Loiter.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -123,8 +123,8 @@ void AC_Loiter::init_target()
123123

124124
// initialise predicted acceleration and angles from the position controller
125125
_predicted_accel_ne_cmss = _pos_control.get_accel_target_NEU_cmss().xy();
126-
_predicted_euler_angle_rad.x = radians(_pos_control.get_roll_cd() * 0.01f);
127-
_predicted_euler_angle_rad.y = radians(_pos_control.get_pitch_cd() * 0.01f);
126+
_predicted_euler_angle_rad.x = _pos_control.get_roll_cd() * radians(0.01f);
127+
_predicted_euler_angle_rad.y = _pos_control.get_pitch_cd() * radians(0.01f);
128128
_brake_accel_cmss = 0.0f;
129129
}
130130

@@ -140,8 +140,8 @@ void AC_Loiter::set_pilot_desired_acceleration_cd(float euler_roll_angle_cd, flo
140140
{
141141
const float dt = _attitude_control.get_dt();
142142
// Convert from centidegrees on public interface to radians
143-
const float euler_roll_angle_rad = radians(euler_roll_angle_cd * 0.01f);
144-
const float euler_pitch_angle_rad = radians(euler_pitch_angle_cd * 0.01f);
143+
const float euler_roll_angle_rad = euler_roll_angle_cd * radians(0.01f);
144+
const float euler_pitch_angle_rad = euler_pitch_angle_cd * radians(0.01f);
145145

146146
// convert our desired attitude to an acceleration vector assuming we are not accelerating vertically
147147
const Vector3f desired_euler_rad {euler_roll_angle_rad, euler_pitch_angle_rad, _ahrs.yaw};

libraries/AP_L1_Control/AP_L1_Control.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -498,11 +498,11 @@ void AP_L1_Control::update_heading_hold(int32_t navigation_heading_cd)
498498

499499
// copy to _target_bearing_cd and _nav_bearing
500500
_target_bearing_cd = wrap_180_cd(navigation_heading_cd);
501-
_nav_bearing = radians(navigation_heading_cd * 0.01f);
501+
_nav_bearing = navigation_heading_cd * radians(0.01f);
502502

503503
Nu_cd = _target_bearing_cd - wrap_180_cd(_ahrs.yaw_sensor);
504504
Nu_cd = wrap_180_cd(Nu_cd);
505-
Nu = radians(Nu_cd * 0.01f);
505+
Nu = Nu_cd * radians(0.01f);
506506

507507
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
508508

libraries/AP_Mount/AP_Mount_Topotek.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -960,9 +960,9 @@ void AP_Mount_Topotek::gimbal_angle_analyse()
960960
int16_t roll_angle_cd = hexchar4_to_int16(_msg_buff[18], _msg_buff[19], _msg_buff[20], _msg_buff[21]);
961961

962962
// convert cd to radians
963-
_current_angle_rad.x = radians(roll_angle_cd * 0.01);
964-
_current_angle_rad.y = radians(pitch_angle_cd * 0.01);
965-
_current_angle_rad.z = radians(yaw_angle_cd * 0.01);
963+
_current_angle_rad.x = roll_angle_cd * radians(0.01);
964+
_current_angle_rad.y = pitch_angle_cd * radians(0.01);
965+
_current_angle_rad.z = yaw_angle_cd * radians(0.01);
966966
_last_current_angle_ms = AP_HAL::millis();
967967

968968
return;

libraries/AP_Mount/AP_Mount_Xacti.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -501,7 +501,7 @@ void AP_Mount_Xacti::handle_gimbal_attitude_status(AP_DroneCAN* ap_dronecan, con
501501
}
502502

503503
// convert body-frame Euler angles to Quaternion. Note yaw direction is reversed from normal
504-
driver->_current_attitude_quat.from_euler(radians(msg.gimbal_roll * 0.01), radians(msg.gimbal_pitch * 0.01), radians(-msg.gimbal_yaw * 0.01));
504+
driver->_current_attitude_quat.from_euler(msg.gimbal_roll * radians(0.01), msg.gimbal_pitch * radians(0.01), -msg.gimbal_yaw * radians(0.01));
505505
driver->_last_current_attitude_quat_ms = AP_HAL::millis();
506506
}
507507

libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -468,7 +468,7 @@ void NavEKF2_core::recordYawReset()
468468
bool NavEKF2_core::checkGyroCalStatus(void)
469469
{
470470
// check delta angle bias variances
471-
const ftype delAngBiasVarMax = sq(radians(0.15f * dtEkfAvg));
471+
const ftype delAngBiasVarMax = sq(radians(0.15f) * dtEkfAvg);
472472
if (!use_compass()) {
473473
// rotate the variances into earth frame and evaluate horizontal terms only as yaw component is poorly observable without a compass
474474
// which can make this check fail

libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1575,10 +1575,10 @@ void NavEKF2_core::ConstrainStates()
15751575
// calculate the NED earth spin vector in rad/sec
15761576
void NavEKF2_core::calcEarthRateNED(Vector3F &omega, int32_t latitude) const
15771577
{
1578-
ftype lat_rad = radians(latitude*1.0e-7f);
1579-
omega.x = earthRate*cosF(lat_rad);
1578+
ftype lat_rad = latitude * radians(1.0e-7f);
1579+
omega.x = earthRate * cosF(lat_rad);
15801580
omega.y = 0;
1581-
omega.z = -earthRate*sinF(lat_rad);
1581+
omega.z = -earthRate * sinF(lat_rad);
15821582
}
15831583

15841584
// initialise the earth magnetic field states using declination, suppled roll/pitch

libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -739,7 +739,7 @@ void NavEKF3_core::recordYawResetsCompleted()
739739
void NavEKF3_core::checkGyroCalStatus(void)
740740
{
741741
// check delta angle bias variances
742-
const ftype delAngBiasVarMax = sq(radians(0.15 * dtEkfAvg));
742+
const ftype delAngBiasVarMax = sq(radians(0.15) * dtEkfAvg);
743743
if (!use_compass() && (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS) && (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) &&
744744
(yaw_source_last != AP_NavEKF_Source::SourceYaw::EXTNAV)) {
745745
// rotate the variances into earth frame and evaluate horizontal terms only as yaw component is poorly observable without a yaw reference

libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2062,7 +2062,7 @@ void NavEKF3_core::ConstrainStates()
20622062
// calculate the NED earth spin vector in rad/sec
20632063
void NavEKF3_core::calcEarthRateNED(Vector3F &omega, int32_t latitude) const
20642064
{
2065-
ftype lat_rad = radians(latitude*1.0e-7f);
2065+
ftype lat_rad = latitude * radians(1.0e-7f);
20662066
omega.x = earthRate*cosF(lat_rad);
20672067
omega.y = 0;
20682068
omega.z = -earthRate*sinF(lat_rad);

libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class OpticalFlow_backend
5858
Vector2f _flowScaler(void) const { return Vector2f(frontend._flowScalerX, frontend._flowScalerY); }
5959

6060
// get the yaw angle in radians
61-
float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }
61+
float _yawAngleRad(void) const { return float(frontend._yawAngle_cd) * radians(0.01f); }
6262

6363
// apply yaw angle to a vector
6464
void _applyYaw(Vector2f &v);

0 commit comments

Comments
 (0)