|
|
@ -1,4 +1,8 @@ |
|
|
|
#include <AP_Gripper/AP_Gripper_Servo.h> |
|
|
|
#include <AP_Gripper/AP_Gripper_Servo.h> |
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h> |
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|
|
|
|
#include <SITL/SITL.h> |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
|
@ -13,6 +17,11 @@ void AP_Gripper_Servo::grab() |
|
|
|
// move the servo to the grab position
|
|
|
|
// move the servo to the grab position
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); |
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); |
|
|
|
action_timestamp = AP_HAL::millis(); |
|
|
|
action_timestamp = AP_HAL::millis(); |
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|
|
|
|
is_releasing = false; |
|
|
|
|
|
|
|
is_released = true; |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void AP_Gripper_Servo::release() |
|
|
|
void AP_Gripper_Servo::release() |
|
|
@ -20,6 +29,11 @@ void AP_Gripper_Servo::release() |
|
|
|
// move the servo to the release position
|
|
|
|
// move the servo to the release position
|
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); |
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); |
|
|
|
action_timestamp = AP_HAL::millis(); |
|
|
|
action_timestamp = AP_HAL::millis(); |
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|
|
|
|
is_releasing = true; |
|
|
|
|
|
|
|
is_released = false; |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const |
|
|
|
bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const |
|
|
@ -35,11 +49,23 @@ bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const |
|
|
|
// (e.g. last action was a grab not a release)
|
|
|
|
// (e.g. last action was a grab not a release)
|
|
|
|
return false; |
|
|
|
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) { |
|
|
|
if (AP_HAL::millis() - action_timestamp < action_time) { |
|
|
|
// servo still moving....
|
|
|
|
// servo still moving....
|
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
|
|
|
|
#endif |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -54,7 +80,15 @@ bool AP_Gripper_Servo::grabbed() const |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// type-specific periodic updates:
|
|
|
|
// type-specific periodic updates:
|
|
|
|
void AP_Gripper_Servo::update_gripper() { }; |
|
|
|
void AP_Gripper_Servo::update_gripper() { |
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|
|
|
|
if (is_releasing && !is_released) { |
|
|
|
|
|
|
|
is_released = released(); |
|
|
|
|
|
|
|
} else if (!is_releasing && is_released) { |
|
|
|
|
|
|
|
is_released = !grabbed(); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
bool AP_Gripper_Servo::valid() const |
|
|
|
bool AP_Gripper_Servo::valid() const |
|
|
|
{ |
|
|
|
{ |
|
|
|