mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Made loiter rad smaller in storage
This commit is contained in:
parent
7feecf3220
commit
556db68d2d
@ -316,7 +316,7 @@ public:
|
|||||||
command_index (0, k_param_command_index, PSTR("WP_INDEX")),
|
command_index (0, k_param_command_index, PSTR("WP_INDEX")),
|
||||||
command_nav_index (0, k_param_command_nav_index, PSTR("WP_MUST_INDEX")),
|
command_nav_index (0, k_param_command_nav_index, PSTR("WP_MUST_INDEX")),
|
||||||
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
|
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
|
||||||
loiter_radius (LOITER_RADIUS * 100, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
|
loiter_radius (LOITER_RADIUS, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
|
||||||
waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")),
|
waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")),
|
||||||
crosstrack_gain (CROSSTRACK_GAIN, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")),
|
crosstrack_gain (CROSSTRACK_GAIN, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")),
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user