mirror of https://github.com/ArduPilot/ardupilot
Rover: move gripper up to AP_Vehicle
also make the singleton return a reference rather than a pointer
This commit is contained in:
parent
ccc9231c67
commit
c26bb2b33b
|
@ -1,5 +1,7 @@
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
|
#include <AP_Gripper/AP_Gripper.h>
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Rover parameter definitions
|
Rover parameter definitions
|
||||||
*/
|
*/
|
||||||
|
@ -580,11 +582,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),
|
AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),
|
||||||
|
|
||||||
#if AP_GRIPPER_ENABLED
|
// 39 was AP_Gripper
|
||||||
// @Group: GRIP_
|
|
||||||
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
|
|
||||||
AP_SUBGROUPINFO(gripper, "GRIP_", 39, ParametersG2, AP_Gripper),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Param: BAL_PITCH_TRIM
|
// @Param: BAL_PITCH_TRIM
|
||||||
// @DisplayName: Balance Bot pitch trim angle
|
// @DisplayName: Balance Bot pitch trim angle
|
||||||
|
@ -923,6 +921,21 @@ void Rover::load_parameters(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
|
||||||
|
#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 gripper_old_index = 39; // Old parameter index in g2
|
||||||
|
const uint16_t gripper_old_top_element = 4071; // 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, gripper_old_index, gripper_old_top_element, false);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6
|
// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6
|
||||||
#if HAL_LOGGING_ENABLED
|
#if HAL_LOGGING_ENABLED
|
||||||
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
|
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
|
||||||
|
|
|
@ -8,7 +8,6 @@
|
||||||
#include <AP_AIS/AP_AIS.h>
|
#include <AP_AIS/AP_AIS.h>
|
||||||
#include <AP_Beacon/AP_Beacon.h>
|
#include <AP_Beacon/AP_Beacon.h>
|
||||||
#include <AP_Follow/AP_Follow.h>
|
#include <AP_Follow/AP_Follow.h>
|
||||||
#include "AP_Gripper/AP_Gripper.h"
|
|
||||||
#include <AP_Proximity/AP_Proximity.h>
|
#include <AP_Proximity/AP_Proximity.h>
|
||||||
#include "AP_Rally.h"
|
#include "AP_Rally.h"
|
||||||
#include <AP_SmartRTL/AP_SmartRTL.h>
|
#include <AP_SmartRTL/AP_SmartRTL.h>
|
||||||
|
@ -372,10 +371,6 @@ public:
|
||||||
AC_Sprayer sprayer;
|
AC_Sprayer sprayer;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_GRIPPER_ENABLED
|
|
||||||
AP_Gripper gripper;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAL_RALLY_ENABLED
|
#if HAL_RALLY_ENABLED
|
||||||
// Rally point library
|
// Rally point library
|
||||||
AP_Rally_Rover rally;
|
AP_Rally_Rover rally;
|
||||||
|
|
|
@ -35,8 +35,6 @@
|
||||||
#include "version.h"
|
#include "version.h"
|
||||||
#undef FORCE_VERSION_H_INCLUDE
|
#undef FORCE_VERSION_H_INCLUDE
|
||||||
|
|
||||||
#include "AP_Gripper/AP_Gripper.h"
|
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
#define SCHED_TASK(func, _interval_ticks, _max_time_micros, _priority) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros, _priority)
|
#define SCHED_TASK(func, _interval_ticks, _max_time_micros, _priority) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros, _priority)
|
||||||
|
@ -101,9 +99,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||||
#if AP_SERVORELAYEVENTS_ENABLED
|
#if AP_SERVORELAYEVENTS_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
|
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
|
||||||
#endif
|
#endif
|
||||||
#if AP_GRIPPER_ENABLED
|
|
||||||
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
|
||||||
#endif
|
|
||||||
#if AC_PRECLAND_ENABLED
|
#if AC_PRECLAND_ENABLED
|
||||||
SCHED_TASK(update_precland, 400, 50, 70),
|
SCHED_TASK(update_precland, 400, 50, 70),
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -14,11 +14,6 @@ static void failsafe_check_static()
|
||||||
|
|
||||||
void Rover::init_ardupilot()
|
void Rover::init_ardupilot()
|
||||||
{
|
{
|
||||||
// init gripper
|
|
||||||
#if AP_GRIPPER_ENABLED
|
|
||||||
g2.gripper.init();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// initialise notify system
|
// initialise notify system
|
||||||
notify.init();
|
notify.init();
|
||||||
notify_mode(control_mode);
|
notify_mode(control_mode);
|
||||||
|
|
Loading…
Reference in New Issue