mirror of https://github.com/ArduPilot/ardupilot
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:
parent
9b5246735e
commit
28690d66b2
|
@ -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;
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue