diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index 364db037b6..9739527fe7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -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 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 86b28e38a4..82c39da0db 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -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 diff --git a/docs/en/peripherals/gripper.md b/docs/en/peripherals/gripper.md index 66c75d3ec7..07886d70ca 100644 --- a/docs/en/peripherals/gripper.md +++ b/docs/en/peripherals/gripper.md @@ -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). diff --git a/src/modules/payload_deliverer/module.yaml b/src/modules/payload_deliverer/module.yaml index fd193052a3..1fefaf7a14 100644 --- a/src/modules/payload_deliverer/module.yaml +++ b/src/modules/payload_deliverer/module.yaml @@ -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 diff --git a/src/modules/payload_deliverer/payload_deliverer.cpp b/src/modules/payload_deliverer/payload_deliverer.cpp index 0edb3a5270..f68913164b 100644 --- a/src/modules/payload_deliverer/payload_deliverer.cpp +++ b/src/modules/payload_deliverer/payload_deliverer.cpp @@ -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 diff --git a/src/modules/payload_deliverer/payload_deliverer.h b/src/modules/payload_deliverer/payload_deliverer.h index 39b4cf4a15..fa68f4faa5 100644 --- a/src/modules/payload_deliverer/payload_deliverer.h +++ b/src/modules/payload_deliverer/payload_deliverer.h @@ -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) _param_gripper_timeout_s, - (ParamInt) _param_gripper_type, - (ParamBool) _param_gripper_enable + (ParamInt) _param_gripper_type ) };