mirror of https://github.com/ArduPilot/ardupilot
AP_Gripper: add parameter unit and remove print on grab or release
This commit is contained in:
parent
d9cbcd9487
commit
039d12bd55
|
@ -52,6 +52,7 @@ const AP_Param::GroupInfo AP_Gripper::var_info[] = {
|
|||
// @Description: Time in seconds that gripper will regrab the cargo to ensure grip has not weakened; 0 to disable
|
||||
// @User: Advanced
|
||||
// @Values: 0 255
|
||||
// @Units: seconds
|
||||
AP_GROUPINFO("REGRAB", 5, AP_Gripper, config.regrab_interval, GRIPPER_REGRAB_DEFAULT),
|
||||
|
||||
// @Param: UAVCAN_ID
|
||||
|
|
|
@ -48,7 +48,6 @@ void AP_Gripper_EPM::grab()
|
|||
|
||||
#ifdef UAVCAN_IOCS_HARDPOINT_SET
|
||||
if (should_use_uavcan()) {
|
||||
::printf("EPM: UAVCAN GRAB\n");
|
||||
const UAVCANCommand cmd = make_uavcan_command(1);
|
||||
(void)ioctl(_uavcan_fd, UAVCAN_IOCS_HARDPOINT_SET, reinterpret_cast<unsigned long>(&cmd));
|
||||
}
|
||||
|
@ -71,7 +70,6 @@ void AP_Gripper_EPM::release()
|
|||
|
||||
#ifdef UAVCAN_IOCS_HARDPOINT_SET
|
||||
if (should_use_uavcan()) {
|
||||
::printf("EPM: UAVCAN RELEASE\n");
|
||||
const UAVCANCommand cmd = make_uavcan_command(0);
|
||||
(void)ioctl(_uavcan_fd, UAVCAN_IOCS_HARDPOINT_SET, reinterpret_cast<unsigned long>(&cmd));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue