mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: create generic vehicle management and move runcam to it
This commit is contained in:
parent
0eddc8b589
commit
93abfdb905
@ -49,7 +49,6 @@
|
|||||||
//#define OSD_ENABLED DISABLED // disable on-screen-display support
|
//#define OSD_ENABLED DISABLED // disable on-screen-display support
|
||||||
//#define BUTTON_ENABLED DISABLED // disable button support
|
//#define BUTTON_ENABLED DISABLED // disable button support
|
||||||
|
|
||||||
|
|
||||||
// features below are disabled by default on all boards
|
// features below are disabled by default on all boards
|
||||||
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
||||||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
||||||
|
@ -623,5 +623,6 @@ Copter::Copter(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
Copter copter;
|
Copter copter;
|
||||||
|
AP_Vehicle& vehicle = copter;
|
||||||
|
|
||||||
AP_HAL_MAIN_CALLBACKS(&copter);
|
AP_HAL_MAIN_CALLBACKS(&copter);
|
||||||
|
@ -715,6 +715,10 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// @Path: Parameters.cpp
|
// @Path: Parameters.cpp
|
||||||
GOBJECT(g2, "", ParametersG2),
|
GOBJECT(g2, "", ParametersG2),
|
||||||
|
|
||||||
|
// @Group:
|
||||||
|
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
|
||||||
|
{ AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&copter, {group_info : AP_Vehicle::var_info} },
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -959,8 +963,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),
|
AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -373,6 +373,8 @@ public:
|
|||||||
|
|
||||||
// 254,255: reserved
|
// 254,255: reserved
|
||||||
|
|
||||||
|
k_param_vehicle = 257, // vehicle common block of parameters
|
||||||
|
|
||||||
// the k_param_* space is 9-bits in size
|
// the k_param_* space is 9-bits in size
|
||||||
// 511: reserved
|
// 511: reserved
|
||||||
};
|
};
|
||||||
|
@ -226,6 +226,9 @@ void Copter::init_ardupilot()
|
|||||||
g2.smart_rtl.init();
|
g2.smart_rtl.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// run all the vehicle initialization routines
|
||||||
|
init_vehicle();
|
||||||
|
|
||||||
// initialise AP_Logger library
|
// initialise AP_Logger library
|
||||||
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
|
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user