mirror of https://github.com/ArduPilot/ardupilot
ArduSub: move gripper up to AP_Vehicle
also make the singleton return a reference rather than a pointer
This commit is contained in:
parent
d2d89b02cc
commit
ccc9231c67
|
@ -102,9 +102,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66),
|
||||
#endif
|
||||
SCHED_TASK(terrain_update, 10, 100, 72),
|
||||
#if AP_GRIPPER_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75, 75),
|
||||
#endif
|
||||
#if AP_STATS_ENABLED
|
||||
SCHED_TASK(stats_update, 1, 200, 76),
|
||||
#endif
|
||||
|
|
|
@ -1,5 +1,7 @@
|
|||
#include "Sub.h"
|
||||
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -693,11 +695,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_SUBGROUPINFO(proximity, "PRX", 2, ParametersG2, AP_Proximity),
|
||||
#endif
|
||||
|
||||
#if AP_GRIPPER_ENABLED
|
||||
// @Group: GRIP_
|
||||
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
|
||||
AP_SUBGROUPINFO(gripper, "GRIP_", 3, ParametersG2, AP_Gripper),
|
||||
#endif
|
||||
// 3 was AP_Gripper
|
||||
|
||||
// @Group: SERVO
|
||||
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
|
||||
|
@ -791,6 +789,21 @@ void Sub::load_parameters()
|
|||
}
|
||||
#endif
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Feb-2024
|
||||
#if AP_GRIPPER_ENABLED
|
||||
{
|
||||
// Find G2's Top Level Key
|
||||
AP_Param::ConversionInfo gripper_info;
|
||||
if (!AP_Param::find_top_level_key_by_pointer(&g2, gripper_info.old_key)) {
|
||||
return;
|
||||
}
|
||||
|
||||
const uint16_t old_gripper_index = 3; // Old parameter index in g2
|
||||
const uint16_t old_gripper_top_element = 4035; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||
AP_Param::convert_class(gripper_info.old_key, &gripper, gripper.var_info, old_gripper_index, old_gripper_top_element, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Feb-2024
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
|
||||
|
|
|
@ -4,7 +4,6 @@
|
|||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
|
||||
// Global parameter class.
|
||||
|
@ -353,10 +352,6 @@ public:
|
|||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
#if AP_GRIPPER_ENABLED
|
||||
AP_Gripper gripper;
|
||||
#endif
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
// proximity (aka object avoidance) library
|
||||
AP_Proximity proximity;
|
||||
|
|
|
@ -88,11 +88,6 @@
|
|||
#include <AP_RPM/AP_RPM.h>
|
||||
#endif
|
||||
|
||||
#include <AP_Gripper/AP_Gripper_config.h>
|
||||
#if AP_GRIPPER_ENABLED
|
||||
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
|
||||
#endif
|
||||
|
||||
#if AVOIDANCE_ENABLED == ENABLED
|
||||
#include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
|
||||
#endif
|
||||
|
|
|
@ -14,11 +14,6 @@ static void failsafe_check_static()
|
|||
|
||||
void Sub::init_ardupilot()
|
||||
{
|
||||
// init cargo gripper
|
||||
#if AP_GRIPPER_ENABLED
|
||||
g2.gripper.init();
|
||||
#endif
|
||||
|
||||
// initialise notify system
|
||||
notify.init();
|
||||
|
||||
|
|
Loading…
Reference in New Issue