AP_Gripper: stop cheating on simulated servo state

This commit is contained in:
Peter Barker 2018-10-04 10:01:39 +10:00 committed by Andrew Tridgell
parent 7af119b497
commit e0f63ca7f1
1 changed files with 7 additions and 12 deletions

View File

@ -49,23 +49,18 @@ bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const
// (e.g. last action was a grab not a release)
return false;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (is_releasing && AP::sitl()->gripper_sim.is_jaw_open()) {
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released");
return true;
}
if (!is_releasing && !AP::sitl()->gripper_sim.is_jaw_open()) {
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed");
return true;
}
return false;
#else
if (AP_HAL::millis() - action_timestamp < action_time) {
// servo still moving....
return false;
}
return true;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (is_releasing) {
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released");
} else {
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed");
}
#endif
return true;
}