mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 14:24:21 +08:00
payload deliverer: remove PD_GRIPPER_EN as unnecessary, reduce gripper timeout to 1s
This commit is contained in:
@@ -345,11 +345,7 @@ then
|
||||
gyro_calibration start
|
||||
fi
|
||||
|
||||
# Payload deliverer module if gripper is enabled
|
||||
if param compare -s PD_GRIPPER_EN 1
|
||||
then
|
||||
payload_deliverer start
|
||||
fi
|
||||
payload_deliverer start
|
||||
|
||||
if param compare -s ICE_EN 1
|
||||
then
|
||||
|
||||
@@ -568,11 +568,7 @@ else
|
||||
px4flow start -X &
|
||||
fi
|
||||
|
||||
# Payload deliverer module if gripper is enabled
|
||||
if param compare -s PD_GRIPPER_EN 1
|
||||
then
|
||||
payload_deliverer start
|
||||
fi
|
||||
payload_deliverer start
|
||||
|
||||
if param compare -s ICE_EN 1
|
||||
then
|
||||
|
||||
@@ -38,7 +38,7 @@ MAVLink applications, such as ground stations, can also control the gripper usin
|
||||
|
||||
PX4 gripper support is tied to the package delivery feature, which must be enabled and configured in order to be able to use a gripper.
|
||||
|
||||
1. Set [PD_GRIPPER_EN](../advanced_config/parameter_reference.md#PD_GRIPPER_EN) parameter to 1 (reboot required after change).
|
||||
1. Ensure your board has the Payload Deliverer module enabled: CONFIG_MODULES_PAYLOAD_DELIVERER.
|
||||
1. Set [PD_GRIPPER_TYPE](../advanced_config/parameter_reference.md#PD_GRIPPER_TYPE) to match your gripper.
|
||||
For example, set to `Servo` for a [Servo Gripper](gripper_servo.md).
|
||||
|
||||
|
||||
@@ -5,13 +5,6 @@ parameters:
|
||||
definitions:
|
||||
|
||||
# Gripper configuration
|
||||
PD_GRIPPER_EN:
|
||||
description:
|
||||
short: Enable Gripper actuation in Payload Deliverer
|
||||
type: boolean
|
||||
default: 0
|
||||
reboot_required: true
|
||||
|
||||
PD_GRIPPER_TYPE:
|
||||
description:
|
||||
short: Type of Gripper (Servo, etc.)
|
||||
@@ -34,4 +27,4 @@ parameters:
|
||||
type: float
|
||||
unit: s
|
||||
min: 0
|
||||
default: 3
|
||||
default: 1
|
||||
|
||||
@@ -54,7 +54,7 @@ bool PayloadDeliverer::init()
|
||||
void PayloadDeliverer::configure_gripper()
|
||||
{
|
||||
// If gripper instance is invalid, and user enabled the gripper, try initializing it
|
||||
if (!_gripper.is_valid() && _param_gripper_enable.get()) {
|
||||
if (!_gripper.is_valid()) {
|
||||
GripperConfig config{};
|
||||
config.type = (GripperConfig::GripperType)_param_gripper_type.get();
|
||||
config.sensor = GripperConfig::GripperSensorType::NONE; // Feedback sensor isn't supported for now
|
||||
|
||||
@@ -104,7 +104,7 @@ private:
|
||||
/**
|
||||
* @brief Initialize or deinitialize gripper instance based on parameter settings
|
||||
*
|
||||
* Depending on `PD_GRIPPER_EN` and the state of `_gripper` instance, this function will
|
||||
* Depending on the state of `_gripper` instance, this function will
|
||||
* either try to initialize or de-initialize the gripper appropriately.
|
||||
*/
|
||||
void configure_gripper();
|
||||
@@ -159,7 +159,6 @@ private:
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamFloat<px4::params::PD_GRIPPER_TO>) _param_gripper_timeout_s,
|
||||
(ParamInt<px4::params::PD_GRIPPER_TYPE>) _param_gripper_type,
|
||||
(ParamBool<px4::params::PD_GRIPPER_EN>) _param_gripper_enable
|
||||
(ParamInt<px4::params::PD_GRIPPER_TYPE>) _param_gripper_type
|
||||
)
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user