RCMap: added RebootRequired param description

This commit is contained in:
Randy Mackay 2015-05-28 19:31:49 +09:00
parent b02bbcd289
commit 19b021f729
1 changed files with 8 additions and 4 deletions

View File

@ -6,34 +6,38 @@
const AP_Param::GroupInfo RCMapper::var_info[] PROGMEM = { const AP_Param::GroupInfo RCMapper::var_info[] PROGMEM = {
// @Param: ROLL // @Param: ROLL
// @DisplayName: Roll channel // @DisplayName: Roll channel
// @Description: Reboot is required for changes to take effect. Roll channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Roll is normally on channel 1, but you can move it to any channel with this parameter. // @Description: Roll channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Roll is normally on channel 1, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
// @Range: 1 8 // @Range: 1 8
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1), AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1),
// @Param: PITCH // @Param: PITCH
// @DisplayName: Pitch channel // @DisplayName: Pitch channel
// @Description: Reboot is required for changes to take effect. Pitch channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Pitch is normally on channel 2, but you can move it to any channel with this parameter. // @Description: Pitch channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Pitch is normally on channel 2, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
// @Range: 1 8 // @Range: 1 8
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2), AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2),
// @Param: THROTTLE // @Param: THROTTLE
// @DisplayName: Throttle channel // @DisplayName: Throttle channel
// @Description: Reboot is required for changes to take effect. Throttle channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Throttle is normally on channel 3, but you can move it to any channel with this parameter. Warning APM 2.X: Changing the throttle channel could produce unexpected fail-safe results if connection between receiver and on-board PPM Encoder is lost. Disabling on-board PPM Encoder is recommended. // @Description: Throttle channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Throttle is normally on channel 3, but you can move it to any channel with this parameter. Warning APM 2.X: Changing the throttle channel could produce unexpected fail-safe results if connection between receiver and on-board PPM Encoder is lost. Disabling on-board PPM Encoder is recommended. Reboot is required for changes to take effect.
// @Range: 1 8 // @Range: 1 8
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3), AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3),
// @Param: YAW // @Param: YAW
// @DisplayName: Yaw channel // @DisplayName: Yaw channel
// @Description: Reboot is required for changes to take effect. Yaw channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Yaw (also known as rudder) is normally on channel 4, but you can move it to any channel with this parameter. // @Description: Yaw channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Yaw (also known as rudder) is normally on channel 4, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
// @Range: 1 8 // @Range: 1 8
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4), AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
AP_GROUPEND AP_GROUPEND