mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
Improve parameter documentation, it still does not work, but is an improvement.
I just do not understand why these parameters do not appear in Mission planner :(
This commit is contained in:
parent
c0f8f6251b
commit
1da0ce20ce
@ -6,7 +6,6 @@
|
|||||||
#include <AP_Mount.h>
|
#include <AP_Mount.h>
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
||||||
// index 0 was used for the old orientation matrix
|
|
||||||
// @Param: MODE
|
// @Param: MODE
|
||||||
// @DisplayName: Mount operation mode
|
// @DisplayName: Mount operation mode
|
||||||
// @Description: Camera or antenna mount operation mode
|
// @Description: Camera or antenna mount operation mode
|
||||||
@ -17,27 +16,27 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Param: RETRACT
|
// @Param: RETRACT
|
||||||
// @DisplayName: Mount retract angles
|
// @DisplayName: Mount retract angles
|
||||||
// @Description: Mount angles when in retract operation mode
|
// @Description: Mount angles when in retract operation mode
|
||||||
// @Units: Degrees
|
// @Units: centi-Degrees
|
||||||
// @Range: -180 180
|
// @Range: -18000 17999
|
||||||
// @Increment: .01
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RETRACT", 1, AP_Mount, _retract_angles),
|
AP_GROUPINFO("RETRACT", 1, AP_Mount, _retract_angles),
|
||||||
|
|
||||||
// @Param: NEUTRAL
|
// @Param: NEUTRAL
|
||||||
// @DisplayName: Mount neutral angles
|
// @DisplayName: Mount neutral angles
|
||||||
// @Description: Mount angles when in neutral operation mode
|
// @Description: Mount angles when in neutral operation mode
|
||||||
// @Units: Degrees
|
// @Units: centi-Degrees
|
||||||
// @Range: -180 180
|
// @Range: -18000 17999
|
||||||
// @Increment: .01
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("NEUTRAL", 2, AP_Mount, _neutral_angles),
|
AP_GROUPINFO("NEUTRAL", 2, AP_Mount, _neutral_angles),
|
||||||
|
|
||||||
// @Param: CONTROL
|
// @Param: CONTROL
|
||||||
// @DisplayName: Mount control angles
|
// @DisplayName: Mount control angles
|
||||||
// @Description: Mount angles when in MavLink or RC control operation mode
|
// @Description: Mount angles when in MavLink or RC control operation mode
|
||||||
// @Units: Degrees
|
// @Units: centi-Degrees
|
||||||
// @Range: -180 180
|
// @Range: -18000 17999
|
||||||
// @Increment: .01
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("CONTROL", 3, AP_Mount, _control_angles),
|
AP_GROUPINFO("CONTROL", 3, AP_Mount, _control_angles),
|
||||||
|
|
||||||
|
@ -25,10 +25,44 @@
|
|||||||
APM_RC_Class *RC_Channel::_apm_rc;
|
APM_RC_Class *RC_Channel::_apm_rc;
|
||||||
|
|
||||||
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
||||||
|
// @Param: MIN
|
||||||
|
// @DisplayName: RC min PWM
|
||||||
|
// @Description: RC minimum PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
|
||||||
|
// @Units: ms
|
||||||
|
// @Range: 800 2200
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("MIN", 0, RC_Channel, radio_min),
|
AP_GROUPINFO("MIN", 0, RC_Channel, radio_min),
|
||||||
|
|
||||||
|
// @Param: TRIM
|
||||||
|
// @DisplayName: RC trim PWM
|
||||||
|
// @Description: RC trim (neutral) PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
|
||||||
|
// @Units: ms
|
||||||
|
// @Range: 800 2200
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim),
|
AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim),
|
||||||
|
|
||||||
|
// @Param: MAX
|
||||||
|
// @DisplayName: RC max PWM
|
||||||
|
// @Description: RC maximum PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
|
||||||
|
// @Units: ms
|
||||||
|
// @Range: 800 2200
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("MAX", 2, RC_Channel, radio_max),
|
AP_GROUPINFO("MAX", 2, RC_Channel, radio_max),
|
||||||
|
|
||||||
|
// @Param: REV
|
||||||
|
// @DisplayName: RC reverse
|
||||||
|
// @Description: Reverse servo operation. Ignored unless did switches are disabled.
|
||||||
|
// @Values: 1:Normal,-1:Reversed
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("REV", 3, RC_Channel, _reverse),
|
AP_GROUPINFO("REV", 3, RC_Channel, _reverse),
|
||||||
|
|
||||||
|
// @Param: DZ
|
||||||
|
// @DisplayName: RC dead-zone
|
||||||
|
// @Description: dead zone around trim.
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone),
|
AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -16,18 +16,18 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = {
|
|||||||
// @Param: ANGLE_MIN
|
// @Param: ANGLE_MIN
|
||||||
// @DisplayName: Minimum object position
|
// @DisplayName: Minimum object position
|
||||||
// @Description: Minimum physical angular position of the object that this servo output controls. For example a camera pan angle, an aileron angle, etc
|
// @Description: Minimum physical angular position of the object that this servo output controls. For example a camera pan angle, an aileron angle, etc
|
||||||
// @Units: Degrees
|
// @Units: centi-Degrees
|
||||||
// @Range: -180 180
|
// @Range: -18000 17999
|
||||||
// @Increment: .01
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ANGLE_MIN", 2, RC_Channel_aux, angle_min),
|
AP_GROUPINFO("ANGLE_MIN", 2, RC_Channel_aux, angle_min),
|
||||||
|
|
||||||
// @Param: ANGLE_MAX
|
// @Param: ANGLE_MAX
|
||||||
// @DisplayName: Maximum object position
|
// @DisplayName: Maximum object position
|
||||||
// @Description: Maximum physical angular position of the object that this servo output controls. For example a camera pan angle, an aileron angle, etc
|
// @Description: Maximum physical angular position of the object that this servo output controls. For example a camera pan angle, an aileron angle, etc
|
||||||
// @Units: Degrees
|
// @Units: centi-Degrees
|
||||||
// @Range: -180 180
|
// @Range: -18000 17999
|
||||||
// @Increment: .01
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ANGLE_MAX", 3, RC_Channel_aux, angle_max),
|
AP_GROUPINFO("ANGLE_MAX", 3, RC_Channel_aux, angle_max),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
@ -131,19 +131,11 @@ RC_Channel_aux::output_ch(unsigned char ch_nr)
|
|||||||
/// expects the changes to take effect instantly
|
/// expects the changes to take effect instantly
|
||||||
void update_aux_servo_function(RC_Channel_aux* rc_a, RC_Channel_aux* rc_b, RC_Channel_aux* rc_c, RC_Channel_aux* rc_d)
|
void update_aux_servo_function(RC_Channel_aux* rc_a, RC_Channel_aux* rc_b, RC_Channel_aux* rc_c, RC_Channel_aux* rc_d)
|
||||||
{
|
{
|
||||||
// positions 0..3 of this array never get used, but this is a stack array, so the entire array gets freed at the end of the function
|
|
||||||
RC_Channel_aux::Aux_servo_function_t aux_servo_function[4];
|
RC_Channel_aux::Aux_servo_function_t aux_servo_function[4];
|
||||||
|
aux_servo_function[0] = (rc_a == NULL)?RC_Channel_aux::k_none:(RC_Channel_aux::Aux_servo_function_t)rc_a->function.get();
|
||||||
// initialise array
|
aux_servo_function[1] = (rc_b == NULL)?RC_Channel_aux::k_none:(RC_Channel_aux::Aux_servo_function_t)rc_b->function.get();
|
||||||
aux_servo_function[0] = RC_Channel_aux::k_none;
|
aux_servo_function[2] = (rc_c == NULL)?RC_Channel_aux::k_none:(RC_Channel_aux::Aux_servo_function_t)rc_c->function.get();
|
||||||
aux_servo_function[1] = RC_Channel_aux::k_none;
|
aux_servo_function[3] = (rc_d == NULL)?RC_Channel_aux::k_none:(RC_Channel_aux::Aux_servo_function_t)rc_d->function.get();
|
||||||
aux_servo_function[2] = RC_Channel_aux::k_none;
|
|
||||||
aux_servo_function[3] = RC_Channel_aux::k_none;
|
|
||||||
|
|
||||||
if( rc_a != NULL ) { aux_servo_function[0] = (RC_Channel_aux::Aux_servo_function_t)rc_a->function.get(); }
|
|
||||||
if( rc_b != NULL ) { aux_servo_function[1] = (RC_Channel_aux::Aux_servo_function_t)rc_b->function.get(); }
|
|
||||||
if( rc_c != NULL ) { aux_servo_function[2] = (RC_Channel_aux::Aux_servo_function_t)rc_c->function.get(); }
|
|
||||||
if( rc_d != NULL ) { aux_servo_function[3] = (RC_Channel_aux::Aux_servo_function_t)rc_d->function.get(); }
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < 4; i++) {
|
for (uint8_t i = 0; i < 4; i++) {
|
||||||
if (aux_servo_function[i] >= RC_Channel_aux::k_nr_aux_servo_functions) {
|
if (aux_servo_function[i] >= RC_Channel_aux::k_nr_aux_servo_functions) {
|
||||||
|
Loading…
Reference in New Issue
Block a user