AP_Camera: make trigger dist a float

the parameters and the callers all use float, we unnecessarily lose
precision here

thanks to D Przybysz for finding the issue
This commit is contained in:
Andrew Tridgell 2023-02-07 09:54:29 +11:00
parent 9b5246735e
commit 28690d66b2
2 changed files with 2 additions and 2 deletions

View File

@ -373,7 +373,7 @@ void AP_Camera::update()
return;
}
if (is_zero(_trigg_dist)) {
if (!is_positive(_trigg_dist)) {
_last_location.lat = 0;
_last_location.lng = 0;
return;

View File

@ -50,7 +50,7 @@ public:
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
// set camera trigger distance in a mission
void set_trigger_distance(uint32_t distance_m)
void set_trigger_distance(float distance_m)
{
_trigg_dist.set(distance_m);
}