Skip to content

Commit

Permalink
AP_Camera: explicitly specify floats
Browse files Browse the repository at this point in the history
  • Loading branch information
jaxxzer committed Jun 11, 2018
1 parent 32b8b86 commit c4175be
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -256,8 +256,8 @@ void AP_Camera::send_feedback(mavlink_channel_t chan)
AP::gps().time_epoch_usec(),
0, 0, _image_index,
current_loc.lat, current_loc.lng,
altitude*1e-2, altitude_rel*1e-2,
ahrs.roll_sensor*1e-2, ahrs.pitch_sensor*1e-2, ahrs.yaw_sensor*1e-2,
altitude*1e-2f, altitude_rel*1e-2f,
ahrs.roll_sensor*1e-2f, ahrs.pitch_sensor*1e-2f, ahrs.yaw_sensor*1e-2f,
0.0f, CAMERA_FEEDBACK_PHOTO, _feedback_events);
}

Expand Down Expand Up @@ -287,7 +287,7 @@ void AP_Camera::update()
return;
}

if (_max_roll > 0 && labs(ahrs.roll_sensor*1e-2) > _max_roll) {
if (_max_roll > 0 && labs(ahrs.roll_sensor*1e-2f) > _max_roll) {
return;
}

Expand Down

0 comments on commit c4175be

Please sign in to comment.