APM:Libraries
AP_Gripper_Servo.cpp
Go to the documentation of this file.
2 
3 extern const AP_HAL::HAL& hal;
4 
6 {
7  // move the servo to the release position
8  release();
9 }
10 
12 {
13  // move the servo to the grab position
16 }
17 
19 {
20  // move the servo to the release position
23 }
24 
25 bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const
26 {
27  // return true if servo is in position represented by pwm
28  uint16_t current_pwm;
30  // function not assigned to a channel, perhaps?
31  return false;
32  }
33  if (current_pwm != pwm) {
34  // last action did not set pwm to the current value
35  // (e.g. last action was a grab not a release)
36  return false;
37  }
39  // servo still moving....
40  return false;
41  }
42  return true;
43 }
44 
45 
47 {
49 }
50 
52 {
54 }
55 
56 // type-specific periodic updates:
58 
60 {
62  return false;
63  }
65  return false;
66  }
67  return true;
68 }
const uint16_t action_time
uint32_t action_timestamp
bool released() const override
void release() override
static bool get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static uint16_t pwm
Definition: RCOutput.cpp:20
void grab() override
virtual bool valid() const
bool has_state_pwm(const uint16_t pwm) const
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
uint32_t millis()
Definition: system.cpp:157
void init_gripper() override
void update_gripper() override
bool grabbed() const override
struct AP_Gripper::Backend_Config & config
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)