mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: Change to ternary operator
This commit is contained in:
parent
ec601684e6
commit
d36667c84a
@ -585,27 +585,15 @@ void ModeZigZag::spray(bool b)
|
|||||||
|
|
||||||
uint32_t ModeZigZag::wp_distance() const
|
uint32_t ModeZigZag::wp_distance() const
|
||||||
{
|
{
|
||||||
if (is_auto) {
|
return is_auto ? wp_nav->get_wp_distance_to_destination() : 0;
|
||||||
return wp_nav->get_wp_distance_to_destination();
|
|
||||||
} else {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
int32_t ModeZigZag::wp_bearing() const
|
int32_t ModeZigZag::wp_bearing() const
|
||||||
{
|
{
|
||||||
if (is_auto) {
|
return is_auto ? wp_nav->get_wp_bearing_to_destination() : 0;
|
||||||
return wp_nav->get_wp_bearing_to_destination();
|
|
||||||
} else {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
float ModeZigZag::crosstrack_error() const
|
float ModeZigZag::crosstrack_error() const
|
||||||
{
|
{
|
||||||
if (is_auto) {
|
return is_auto ? wp_nav->crosstrack_error() : 0;
|
||||||
return wp_nav->crosstrack_error();
|
|
||||||
} else {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // MODE_ZIGZAG_ENABLED == ENABLED
|
#endif // MODE_ZIGZAG_ENABLED == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user