Added #define for Tilt_Compensation.

Also added some detail to WP_Speed_Max parameter.
This commit is contained in:
Robert Lefebvre 2012-10-12 14:51:31 -04:00
parent e22a01682e
commit dae81d2068
2 changed files with 19 additions and 5 deletions

View File

@ -120,11 +120,8 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Range: 0 100 // @Range: 0 100
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
#if FRAME_CONFIG == HELI_FRAME GSCALAR(tilt_comp, "TILT", TILT_COMPENSATION),
GSCALAR(tilt_comp, "TILT", 5),
#else
GSCALAR(tilt_comp, "TILT", 54),
#endif
@ -152,7 +149,15 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
GSCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS), GSCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS),
// @Param: WP_SPEED_MAX
// @DisplayName: Waypoint Max Speed Target
// @Description: Defines the speed which the aircraft will attempt to maintain during a WP mission.
// @Units: Centimeters/Second
// @Increment: 100
// @User: Standard
GSCALAR(waypoint_speed_max, "WP_SPEED_MAX", WAYPOINT_SPEED_MAX), GSCALAR(waypoint_speed_max, "WP_SPEED_MAX", WAYPOINT_SPEED_MAX),
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", CROSSTRACK_GAIN), GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", CROSSTRACK_GAIN),
GSCALAR(auto_land_timeout, "AUTO_LAND", AUTO_LAND_TIME*1000), GSCALAR(auto_land_timeout, "AUTO_LAND", AUTO_LAND_TIME*1000),

View File

@ -801,6 +801,15 @@
# define WAYPOINT_SPEED_MIN 150 // 1m/s # define WAYPOINT_SPEED_MIN 150 // 1m/s
#endif #endif
#ifndef TILT_COMPENSATION
# if FRAME_CONFIG == HELI_FRAME
# define TILT_COMPENSATION 5
# else
# define TILT_COMPENSATION 54
# endif
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Throttle control gains // Throttle control gains