mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 00:53:57 -03:00
Camera: use camera feedback flag
This commit is contained in:
parent
26383183d2
commit
18a73d8630
@ -224,7 +224,7 @@ void AP_Camera::send_feedback(mavlink_channel_t chan, AP_GPS &gps, const AP_AHRS
|
|||||||
current_loc.lat, current_loc.lng,
|
current_loc.lat, current_loc.lng,
|
||||||
altitude/100.0f, altitude_rel/100.0f,
|
altitude/100.0f, altitude_rel/100.0f,
|
||||||
ahrs.roll_sensor/100.0f, ahrs.pitch_sensor/100.0f, ahrs.yaw_sensor/100.0f,
|
ahrs.roll_sensor/100.0f, ahrs.pitch_sensor/100.0f, ahrs.yaw_sensor/100.0f,
|
||||||
0.0,0);
|
0.0,CAMERA_FEEDBACK_PHOTO);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user