mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: add AP_GRIPPER_ENABLED
This commit is contained in:
parent
997f8d3d3a
commit
1e4175cc8e
@ -583,7 +583,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 GRIPPER_ENABLED == ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
// @Group: GRIP_
|
// @Group: GRIP_
|
||||||
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
|
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
|
||||||
AP_SUBGROUPINFO(gripper, "GRIP_", 39, ParametersG2, AP_Gripper),
|
AP_SUBGROUPINFO(gripper, "GRIP_", 39, ParametersG2, AP_Gripper),
|
||||||
|
@ -370,7 +370,7 @@ public:
|
|||||||
AC_Sprayer sprayer;
|
AC_Sprayer sprayer;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if GRIPPER_ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
AP_Gripper gripper;
|
AP_Gripper gripper;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -92,7 +92,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||||||
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200, 60),
|
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200, 60),
|
||||||
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300, 63),
|
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300, 63),
|
||||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
|
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
|
||||||
#if GRIPPER_ENABLED == ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED
|
||||||
SCHED_TASK(update_precland, 400, 50, 70),
|
SCHED_TASK(update_precland, 400, 50, 70),
|
||||||
|
@ -31,13 +31,6 @@
|
|||||||
#error XXX
|
#error XXX
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// GRIPPER control
|
|
||||||
//
|
|
||||||
#ifndef GRIPPER_ENABLED
|
|
||||||
# define GRIPPER_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// RALLY POINTS
|
// RALLY POINTS
|
||||||
//
|
//
|
||||||
|
@ -25,7 +25,7 @@ void Rover::init_ardupilot()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// init gripper
|
// init gripper
|
||||||
#if GRIPPER_ENABLED == ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
g2.gripper.init();
|
g2.gripper.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user