ArduPlane: move gripper up to AP_Vehicle

also make the singleton return a reference rather than a pointer
This commit is contained in:
Peter Barker 2024-02-21 17:40:35 +11:00 committed by Peter Barker
parent f2a9f1516b
commit d2d89b02cc
4 changed files with 18 additions and 19 deletions

View File

@ -132,9 +132,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if HAL_BUTTON_ENABLED
SCHED_TASK_CLASS(AP_Button, &plane.button, update, 5, 100, 150),
#endif
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156),
#endif
#if AP_LANDINGGEAR_ENABLED
SCHED_TASK(landing_gear_update, 5, 50, 159),
#endif

View File

@ -1,5 +1,7 @@
#include "Plane.h"
#include <AP_Gripper/AP_Gripper.h>
/*
* ArduPlane parameter definitions
*
@ -1068,11 +1070,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("HOME_RESET_ALT", 11, ParametersG2, home_reset_threshold, 0),
#if AP_GRIPPER_ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO(gripper, "GRIP_", 12, ParametersG2, AP_Gripper),
#endif
// 12 was AP_Gripper
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
@ -1558,6 +1556,21 @@ void Plane::load_parameters(void)
}
#endif
// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6
#if AP_GRIPPER_ENABLED
{
// Find G2's Top Level Key
AP_Param::ConversionInfo info;
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
return;
}
const uint16_t old_index = 12; // Old parameter index in g2
const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
AP_Param::convert_class(info.old_key, &gripper, gripper.var_info, old_index, old_top_element, false);
}
#endif
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
#if HAL_LOGGING_ENABLED
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);

View File

@ -3,7 +3,6 @@
#define AP_PARAM_VEHICLE_NAME plane
#include <AP_Common/AP_Common.h>
#include <AP_Gripper/AP_Gripper.h>
// Global parameter class.
//
@ -512,11 +511,6 @@ public:
// home reset altitude threshold
AP_Int8 home_reset_threshold;
#if AP_GRIPPER_ENABLED
// Payload Gripper
AP_Gripper gripper;
#endif
AP_Int32 flight_options;
AP_Int8 takeoff_throttle_accel_count;

View File

@ -132,11 +132,6 @@ void Plane::init_ardupilot()
optflow.init(-1);
}
#endif
// init cargo gripper
#if AP_GRIPPER_ENABLED
g2.gripper.init();
#endif
}
//********************************************************************************