APM:Libraries
SIM_Gripper_Servo.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simple Gripper (Servo) simulation class
17 */
18 
19 #include "SIM_Gripper_Servo.h"
20 #include <stdio.h>
21 
22 using namespace SITL;
23 
24 /*
25  update gripper state
26  */
28 {
29  const uint64_t now = AP_HAL::micros64();
30  const float dt = (now - last_update_us) * 1.0e-6f;
31 
32  // update gripper position
33 
34  float position_demand = (input.servos[gripper_servo]-1000) * 0.001f;
35  if (position_demand < 0) { // never updated
36  position_demand = 0;
37  }
38 
39  const float position_max_change = position_slew_rate/100.0f * dt;
40  position = constrain_float(position_demand, position-position_max_change, position+position_max_change);
41 
42  const float jaw_gap = gap*(1.0f-position);
43  if (should_report()) {
44  ::fprintf(stderr, "position_demand=%f jaw_gap=%f load=%f\n", position_demand, jaw_gap, load_mass);
45  last_report_us = now;
47  }
48 
49  if (jaw_gap < 5) {
50  if (aircraft->on_ground()) {
51  load_mass = 1.0f; // attach the load
52  }
53  } else if (jaw_gap > 10) {
54  load_mass = 0.0f; // detach the load
55  }
56 
57  last_update_us = now;
58  return;
59 }
60 
62 {
64  return false;
65  }
66 
67  if (reported_position != position) {
68  return true;
69  }
70 
71  return false;
72 }
73 
74 
76 {
77  if (aircraft->hagl() < string_length) {
78  return 0.0f;
79  }
80  return load_mass;
81 }
const uint8_t gripper_servo
void update(const struct Aircraft::sitl_input &input)
const uint32_t report_interval
float hagl() const
virtual bool on_ground() const
#define f(i)
uint64_t micros64()
Definition: system.cpp:162
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
float payload_mass() const