mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
AP_Gripper: add AP_GRIPPER_ENABLED
This commit is contained in:
parent
670a1dbdb1
commit
a3be41c3b0
@ -1,5 +1,7 @@
|
|||||||
#include "AP_Gripper.h"
|
#include "AP_Gripper.h"
|
||||||
|
|
||||||
|
#if AP_GRIPPER_ENABLED
|
||||||
|
|
||||||
#include "AP_Gripper_Servo.h"
|
#include "AP_Gripper_Servo.h"
|
||||||
#include "AP_Gripper_EPM.h"
|
#include "AP_Gripper_EPM.h"
|
||||||
|
|
||||||
@ -109,12 +111,16 @@ void AP_Gripper::init()
|
|||||||
switch(config.type.get()) {
|
switch(config.type.get()) {
|
||||||
case 0:
|
case 0:
|
||||||
break;
|
break;
|
||||||
|
#if AP_GRIPPER_SERVO_ENABLED
|
||||||
case 1:
|
case 1:
|
||||||
backend = new AP_Gripper_Servo(config);
|
backend = new AP_Gripper_Servo(config);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
#if AP_GRIPPER_EPM_ENABLED
|
||||||
case 2:
|
case 2:
|
||||||
backend = new AP_Gripper_EPM(config);
|
backend = new AP_Gripper_EPM(config);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -168,3 +174,5 @@ AP_Gripper *gripper()
|
|||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_ENABLED
|
||||||
|
@ -15,6 +15,10 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_Gripper_config.h"
|
||||||
|
|
||||||
|
#if AP_GRIPPER_ENABLED
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
|
||||||
class AP_Gripper_Backend;
|
class AP_Gripper_Backend;
|
||||||
@ -85,3 +89,5 @@ private:
|
|||||||
namespace AP {
|
namespace AP {
|
||||||
AP_Gripper *gripper();
|
AP_Gripper *gripper();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_ENABLED
|
||||||
|
@ -1,7 +1,8 @@
|
|||||||
#include "AP_Gripper_Backend.h"
|
#include "AP_Gripper_Backend.h"
|
||||||
#include <AP_Math/AP_Math.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
#if AP_GRIPPER_ENABLED
|
||||||
|
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
void AP_Gripper_Backend::init()
|
void AP_Gripper_Backend::init()
|
||||||
{
|
{
|
||||||
@ -20,3 +21,5 @@ void AP_Gripper_Backend::update()
|
|||||||
grab();
|
grab();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_ENABLED
|
||||||
|
@ -17,6 +17,8 @@
|
|||||||
|
|
||||||
#include <AP_Gripper/AP_Gripper.h>
|
#include <AP_Gripper/AP_Gripper.h>
|
||||||
|
|
||||||
|
#if AP_GRIPPER_ENABLED
|
||||||
|
|
||||||
class AP_Gripper_Backend {
|
class AP_Gripper_Backend {
|
||||||
public:
|
public:
|
||||||
AP_Gripper_Backend(struct AP_Gripper::Backend_Config &_config) :
|
AP_Gripper_Backend(struct AP_Gripper::Backend_Config &_config) :
|
||||||
@ -55,3 +57,5 @@ protected:
|
|||||||
|
|
||||||
struct AP_Gripper::Backend_Config &config;
|
struct AP_Gripper::Backend_Config &config;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_ENABLED
|
||||||
|
@ -8,6 +8,9 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_Gripper_EPM.h"
|
#include "AP_Gripper_EPM.h"
|
||||||
|
|
||||||
|
#if AP_GRIPPER_EPM_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
@ -142,3 +145,5 @@ bool AP_Gripper_EPM::grabbed() const
|
|||||||
return (config.state == AP_Gripper::STATE_GRABBED ||
|
return (config.state == AP_Gripper::STATE_GRABBED ||
|
||||||
config.state == AP_Gripper::STATE_GRABBING);
|
config.state == AP_Gripper::STATE_GRABBING);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_EPM_ENABLED
|
||||||
|
@ -14,6 +14,9 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "AP_Gripper.h"
|
#include "AP_Gripper.h"
|
||||||
|
|
||||||
|
#if AP_GRIPPER_EPM_ENABLED
|
||||||
|
|
||||||
#include "AP_Gripper_Backend.h"
|
#include "AP_Gripper_Backend.h"
|
||||||
|
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
@ -57,3 +60,5 @@ private:
|
|||||||
// UAVCAN driver fd
|
// UAVCAN driver fd
|
||||||
int _uavcan_fd = -1;
|
int _uavcan_fd = -1;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_EPM_ENABLED
|
||||||
|
@ -1,4 +1,7 @@
|
|||||||
#include <AP_Gripper/AP_Gripper_Servo.h>
|
#include <AP_Gripper/AP_Gripper_Servo.h>
|
||||||
|
|
||||||
|
#if AP_GRIPPER_SERVO_ENABLED
|
||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
@ -115,3 +118,5 @@ bool AP_Gripper_Servo::valid() const
|
|||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_SERVO_ENABLED
|
||||||
|
@ -16,6 +16,9 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Gripper/AP_Gripper_Backend.h>
|
#include <AP_Gripper/AP_Gripper_Backend.h>
|
||||||
|
|
||||||
|
#if AP_GRIPPER_SERVO_ENABLED
|
||||||
|
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
|
||||||
#define SERVO_ACTUATION_TIME 500 // Time for servo to move to target position during grab or release in milliseconds
|
#define SERVO_ACTUATION_TIME 500 // Time for servo to move to target position during grab or release in milliseconds
|
||||||
@ -53,3 +56,5 @@ private:
|
|||||||
|
|
||||||
bool has_state_pwm(const uint16_t pwm) const;
|
bool has_state_pwm(const uint16_t pwm) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_GRIPPER_SERVO_ENABLED
|
||||||
|
19
libraries/AP_Gripper/AP_Gripper_config.h
Normal file
19
libraries/AP_Gripper/AP_Gripper_config.h
Normal file
@ -0,0 +1,19 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
|
||||||
|
#ifndef AP_GRIPPER_ENABLED
|
||||||
|
#define AP_GRIPPER_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_GRIPPER_BACKEND_DEFAULT_ENABLED
|
||||||
|
#define AP_GRIPPER_BACKEND_DEFAULT_ENABLED AP_GRIPPER_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_GRIPPER_SERVO_ENABLED
|
||||||
|
#define AP_GRIPPER_SERVO_ENABLED AP_GRIPPER_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_GRIPPER_EPM_ENABLED
|
||||||
|
#define AP_GRIPPER_EPM_ENABLED AP_GRIPPER_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
Loading…
Reference in New Issue
Block a user