Rover: enable gripper support

This commit is contained in:
Peter Barker 2019-02-08 10:45:23 +11:00 committed by Randy Mackay
parent 1347083548
commit 9496ffea14
6 changed files with 26 additions and 0 deletions

View File

@ -66,6 +66,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200),
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200),
#if GRIPPER_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75),
#endif
SCHED_TASK(rpm_update, 10, 100),
#if MOUNT == ENABLED
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200),

View File

@ -688,6 +688,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard
AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),
#if GRIPPER_ENABLED == ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO(gripper, "GRIP_", 39, ParametersG2, AP_Gripper),
#endif
AP_GROUPEND
};

View File

@ -371,6 +371,10 @@ public:
// Sprayer
AC_Sprayer sprayer;
#if GRIPPER_ENABLED
AP_Gripper gripper;
#endif
// Rally point library
AP_Rally_Rover rally;

View File

@ -59,6 +59,7 @@
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Gripper/AP_Gripper.h>
#include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_Terrain/AP_Terrain.h>
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build

View File

@ -116,6 +116,13 @@
#define CAMERA ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// GRIPPER control
//
#ifndef GRIPPER_ENABLED
# define GRIPPER_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// RALLY POINTS
//

View File

@ -56,6 +56,11 @@ void Rover::init_ardupilot()
BoardConfig_CAN.init();
#endif
// init gripper
#if GRIPPER_ENABLED == ENABLED
g2.gripper.init();
#endif
// initialise notify system
notify.init();
notify_mode(control_mode);