Sub: Changes based on diff with Copter.

This commit is contained in:
Rustom Jehangir 2016-07-06 12:02:36 -07:00 committed by Andrew Tridgell
parent 814605c461
commit 5adcb2cbef
4 changed files with 20 additions and 79 deletions

View File

@ -148,6 +148,11 @@ NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
if (optflow.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
#if PRECISION_LANDING == ENABLED
if (precland.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
}
#endif
if (ap.rc_receiver_present) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
@ -202,6 +207,11 @@ NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
if (optflow.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
#if PRECISION_LANDING == ENABLED
if (precland.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
}
#endif
if (ap.rc_receiver_present && !failsafe.radio) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
@ -845,7 +855,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK, streamRates[9], 5),
AP_GROUPEND
AP_GROUPEND
};

View File

@ -103,7 +103,7 @@ const AP_Param::Info Sub::var_info[] = {
// @Param: PILOT_THR_BHV
// @DisplayName: Throttle stick behavior
// @Description: Bits for: Feedback starts from mid stick
// @Description: Bitmask containing various throttle stick options. Add up the values for options that you want.
// @User: Standard
// @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
@ -550,11 +550,9 @@ const AP_Param::Info Sub::var_info[] = {
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_8, "RC8_", RC_Channel_aux),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_9, "RC9_", RC_Channel_aux),
#endif
// @Group: RC10_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
@ -563,7 +561,6 @@ const AP_Param::Info Sub::var_info[] = {
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_11, "RC11_", RC_Channel_aux),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// @Group: RC12_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_12, "RC12_", RC_Channel_aux),
@ -575,7 +572,6 @@ const AP_Param::Info Sub::var_info[] = {
// @Group: RC14_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_14, "RC14_", RC_Channel_aux),
#endif
// @Group: BTN0_
// @Path: ../libraries/AP_JSButton/AP_JSButton.cpp
@ -715,12 +711,6 @@ const AP_Param::Info Sub::var_info[] = {
// @Increment: 10
// @Units: cm/s/s
// @User: Advanced
// @Param: VEL_XY_FILT_HZ
// @DisplayName: Velocity (horizontal) filter frequency in Hz
// @Description: Velocity (horizontal) filter frequency in Hz
// @Units: Hz
// @User: Advanced
GGROUP(pi_vel_xy, "VEL_XY_", AC_PI_2D),
// @Param: VEL_Z_P
@ -756,7 +746,7 @@ const AP_Param::Info Sub::var_info[] = {
// @Range: 0.000 0.400
// @User: Standard
// @Param: ACCEL_Z_FILT
// @Param: ACCEL_Z_FILT_HZ
// @DisplayName: Throttle acceleration filter
// @Description: Filter applied to acceleration to reduce noise. Lower values reduce noise but add delay.
// @Range: 1.000 100.000
@ -778,28 +768,6 @@ const AP_Param::Info Sub::var_info[] = {
// @User: Standard
GGROUP(p_pos_xy, "POS_XY_", AC_P),
#if PRECISION_LANDING == ENABLED
// @Param: PRECLNDVEL_P
// @DisplayName: Precision landing velocity controller P gain
// @Description: Precision landing velocity controller P gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: PRECLNDVEL_I
// @DisplayName: Precision landing velocity controller I gain
// @Description: Precision landing velocity controller I gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: PRECLNDVEL_IMAX
// @DisplayName: Precision landing velocity controller I gain maximum
// @Description: Precision landing velocity controller I gain maximum
// @Range: 0 1000
// @Units: cm/s
// @User: Standard
GGROUP(pi_precland, "PLAND_", AC_PI_2D),
#endif
// variables not in the g class which contain EEPROM saved variables
#if CAMERA == ENABLED
@ -848,7 +816,7 @@ const AP_Param::Info Sub::var_info[] = {
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Multi),
// @Group: PSC
// @Group: POSCON_
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
GOBJECT(pos_control, "PSC", AC_PosControl),
@ -979,9 +947,9 @@ const AP_Param::Info Sub::var_info[] = {
#endif
#if PRECISION_LANDING == ENABLED
// @Group: PRECLAND_
// @Group: PLND_
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
GOBJECT(precland, "PLAND_", AC_PrecLand),
GOBJECT(precland, "PLND_", AC_PrecLand),
#endif
// @Group: RPM

View File

@ -361,7 +361,6 @@ public:
k_param_rtl_climb_min,
k_param_rpm_sensor,
k_param_autotune_min_d, // 251
k_param_pi_precland, // 252
k_param_DataFlash = 253, // 253 - Logging Group
// 254,255: reserved
@ -487,16 +486,12 @@ public:
RC_Channel_aux rc_6;
RC_Channel_aux rc_7;
RC_Channel_aux rc_8;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
RC_Channel_aux rc_9;
#endif
RC_Channel_aux rc_10;
RC_Channel_aux rc_11;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
RC_Channel_aux rc_12;
RC_Channel_aux rc_13;
RC_Channel_aux rc_14;
#endif
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
@ -532,10 +527,6 @@ public:
AC_P p_vel_z;
AC_PID pid_accel_z;
#if PRECISION_LANDING == ENABLED
AC_PI_2D pi_precland;
#endif
AC_P p_pos_xy;
AC_P p_alt_hold;
@ -558,16 +549,12 @@ public:
rc_6 (CH_6),
rc_7 (CH_7),
rc_8 (CH_8),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
rc_9 (CH_9),
#endif
rc_10 (CH_10),
rc_11 (CH_11),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
rc_12 (CH_12),
rc_13 (CH_13),
rc_14 (CH_14),
#endif
// PID controller initial P initial I initial D initial imax initial filt hz pid rate
//---------------------------------------------------------------------------------------------------------------------------------
@ -576,10 +563,6 @@ public:
p_vel_z (VEL_Z_P),
pid_accel_z (ACCEL_Z_P, ACCEL_Z_I, ACCEL_Z_D, ACCEL_Z_IMAX, ACCEL_Z_FILT_HZ, MAIN_LOOP_SECONDS),
#if PRECISION_LANDING == ENABLED
pi_precland (PRECLAND_P, PRECLAND_I, PRECLAND_IMAX, VEL_XY_FILT_HZ, PRECLAND_UPDATE_TIME),
#endif
// P controller initial P
//----------------------------------------------------------------------
p_pos_xy (POS_XY_P),

View File

@ -277,6 +277,8 @@ private:
uint32_t start_ms;
} takeoff_state;
uint32_t precland_last_update_ms;
RCMapper rcmap;
// board specific config
@ -308,25 +310,7 @@ private:
} sensor_health;
// Motor Output
#if FRAME_CONFIG == QUAD_FRAME
#define MOTOR_CLASS AP_MotorsQuad
#elif FRAME_CONFIG == TRI_FRAME
#define MOTOR_CLASS AP_MotorsTri
#elif FRAME_CONFIG == HEXA_FRAME
#define MOTOR_CLASS AP_MotorsHexa
#elif FRAME_CONFIG == Y6_FRAME
#define MOTOR_CLASS AP_MotorsY6
#elif FRAME_CONFIG == OCTA_FRAME
#define MOTOR_CLASS AP_MotorsOcta
#elif FRAME_CONFIG == OCTA_QUAD_FRAME
#define MOTOR_CLASS AP_MotorsOctaQuad
#elif FRAME_CONFIG == HELI_FRAME
#define MOTOR_CLASS AP_MotorsHeli_Single
#elif FRAME_CONFIG == SINGLE_FRAME
#define MOTOR_CLASS AP_MotorsSingle
#elif FRAME_CONFIG == COAX_FRAME
#define MOTOR_CLASS AP_MotorsCoax
#elif FRAME_CONFIG == BLUEROV_FRAME
#if FRAME_CONFIG == BLUEROV_FRAME
#define MOTOR_CLASS AP_MotorsBlueROV6DOF
#elif FRAME_CONFIG == VECTORED_FRAME
#define MOTOR_CLASS AP_MotorsVectoredROV
@ -391,7 +375,6 @@ private:
int32_t initial_armed_bearing;
// Throttle variables
float throttle_average; // estimated throttle required to hover
int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only
// Loiter control
@ -666,7 +649,6 @@ private:
void Log_Write_Performance();
void Log_Write_Attitude();
void Log_Write_MotBatt();
void Log_Write_Startup();
void Log_Write_Event(uint8_t id);
void Log_Write_Data(uint8_t id, int32_t value);
void Log_Write_Data(uint8_t id, uint32_t value);
@ -838,13 +820,10 @@ private:
void rtl_land_run();
void rtl_build_path(bool terrain_following_allowed);
void rtl_compute_return_alt(const Location_Class &rtl_origin_point, Location_Class &rtl_return_target, bool terrain_following_allowed);
float get_RTL_alt();
bool sport_init(bool ignore_checks);
void sport_run();
bool stabilize_init(bool ignore_checks);
void stabilize_run();
bool rov_init(bool ignore_checks);
void rov_run();
void crash_check();
void parachute_check();
void parachute_release();
@ -907,6 +886,7 @@ private:
void pre_arm_rc_checks();
bool pre_arm_gps_checks(bool display_failure);
bool pre_arm_ekf_attitude_check();
bool pre_arm_rallypoint_check();
bool pre_arm_terrain_check(bool display_failure);
bool arm_checks(bool display_failure, bool arming_from_gcs);
void init_disarm_motors();