AP_Vehicle: 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 b41d82c989
commit 9bdb886bb8
2 changed files with 23 additions and 0 deletions

View File

@ -270,6 +270,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
AP_SUBGROUPINFO(logger, "LOG", 29, AP_Vehicle, AP_Logger), AP_SUBGROUPINFO(logger, "LOG", 29, AP_Vehicle, AP_Logger),
#endif #endif
#if AP_GRIPPER_ENABLED
// @Group: GRIP_
// @Path: ../AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO(gripper, "GRIP_", 30, AP_Vehicle, AP_Gripper),
#endif
AP_GROUPEND AP_GROUPEND
}; };
@ -382,6 +388,11 @@ void AP_Vehicle::setup()
logger.init(get_log_bitmask(), get_log_structures(), get_num_log_structures()); logger.init(get_log_bitmask(), get_log_structures(), get_num_log_structures());
#endif #endif
// init cargo gripper
#if AP_GRIPPER_ENABLED
AP::gripper().init();
#endif
// init_ardupilot is where the vehicle does most of its initialisation. // init_ardupilot is where the vehicle does most of its initialisation.
init_ardupilot(); init_ardupilot();
@ -606,6 +617,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
#endif #endif
#if HAL_EFI_ENABLED #if HAL_EFI_ENABLED
SCHED_TASK_CLASS(AP_EFI, &vehicle.efi, update, 50, 200, 250), SCHED_TASK_CLASS(AP_EFI, &vehicle.efi, update, 50, 200, 250),
#endif
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &vehicle.gripper, update, 10, 75, 251),
#endif #endif
SCHED_TASK(one_Hz_update, 1, 100, 252), SCHED_TASK(one_Hz_update, 1, 100, 252),
#if HAL_WITH_ESC_TELEM && HAL_GYROFFT_ENABLED #if HAL_WITH_ESC_TELEM && HAL_GYROFFT_ENABLED

View File

@ -75,6 +75,11 @@
#include <AP_Scripting/AP_Scripting.h> #include <AP_Scripting/AP_Scripting.h>
#endif #endif
#include <AP_Gripper/AP_Gripper_config.h>
#if AP_GRIPPER_ENABLED
#include <AP_Gripper/AP_Gripper.h>
#endif
class AP_DDS_Client; class AP_DDS_Client;
class AP_Vehicle : public AP_HAL::HAL::Callbacks { class AP_Vehicle : public AP_HAL::HAL::Callbacks {
@ -330,6 +335,10 @@ protected:
virtual uint8_t get_num_log_structures() const { return 0; } virtual uint8_t get_num_log_structures() const { return 0; }
#endif #endif
#if AP_GRIPPER_ENABLED
AP_Gripper gripper;
#endif
#if AP_RSSI_ENABLED #if AP_RSSI_ENABLED
AP_RSSI rssi; AP_RSSI rssi;
#endif #endif