APM:Libraries
SIM_Gripper_EPM.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 (OpenGrab EPM) simulation class
17 */
18 
19 #include "SIM_Gripper_EPM.h"
20 #include <stdio.h>
21 #include <AP_Common/AP_Common.h>
22 
23 using namespace SITL;
24 
25 /*
26  update gripper state
27  */
29 {
30  if (! servo_based) {
31  return;
32  }
33  demand = (input.servos[gripper_servo]-1000) * 0.001f; // 0.0 - 1.0
34  if (demand < 0) { // never updated
35  demand = 0;
36  }
37 }
38 
39 
41 {
42  const uint64_t now = AP_HAL::micros64();
43  const float dt = (now - last_update_us) * 1.0e-6f;
44 
45  // decay the field
46  field_strength = field_strength * (100-field_decay_rate * dt)/100.0f;
47 
48  // note that "demand" here is just an on/off switch; we only care
49  // about which range it falls into
50  if (demand > 0.6) {
51  // we are instructed to grip harder
53  } else if (demand < 0.4) {
54  // we are instructed to loosen grip
56  } else {
57  // neutral; no demanded change
58  }
59 
60  if (should_report()) {
61  ::fprintf(stderr, "demand=%f\n", demand);
62  printf("Field strength: %f%%\n", field_strength);
63  printf("Field strength: %f Tesla\n", tesla());
64  last_report_us = now;
66  }
67 
68  last_update_us = now;
69  return;
70 }
71 
73 {
74  update_servobased(input);
75 
76  update_from_demand(input);
77 }
78 
79 
81 {
83  return false;
84  }
85 
86  if (fabs(reported_field_strength - field_strength) > 10.0f) {
87  return true;
88  }
89 
90  return false;
91 }
92 
94 {
95  // https://en.wikipedia.org/wiki/Orders_of_magnitude_(magnetic_field)
96  // 200N lifting capacity ~= 2.5T
97  const float percentage_to_tesla = 0.25;
98  return percentage_to_tesla * field_strength/100.0f;
99 }
int printf(const char *fmt,...)
Definition: stdio.c:113
void update_from_demand(const Aircraft::sitl_input &input)
double reported_field_strength
const float field_decay_rate
const float field_degauss_rate
#define f(i)
uint64_t micros64()
Definition: system.cpp:162
const float field_strength_slew_rate
const uint8_t gripper_servo
Common definitions and utility routines for the ArduPilot libraries.
const uint32_t report_interval
void update(const struct Aircraft::sitl_input &input)
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
void update_servobased(const struct Aircraft::sitl_input &input)