APM:Libraries
AP_Gripper_EPM.cpp
Go to the documentation of this file.
1 /*
2  * AP_Gripper_EPM.cpp
3  *
4  * Created on: DEC 6, 2013
5  * Author: Andreas Jochum
6  * Pavel Kirienko <pavel.kirienko@zubax.com> - UAVCAN support
7  * Peter Barker - moved into AP_Gripper_EPM
8  */
9 
10 #include "AP_Gripper_EPM.h"
11 #include <AP_HAL/AP_HAL.h>
13 #ifdef UAVCAN_NODE_FILE
14 #include <fcntl.h>
15 #include <stdio.h>
16 #endif
17 
18 extern const AP_HAL::HAL& hal;
19 
21  AP_Gripper_Backend(_config) { }
22 
24 {
25 #ifdef UAVCAN_NODE_FILE
26  _uavcan_fd = ::open(UAVCAN_NODE_FILE, O_CLOEXEC);
27  // http://ardupilot.org/dev/docs/learning-ardupilot-uarts-and-the-console.html
28  ::printf("EPM: UAVCAN fd %d\n", _uavcan_fd);
29 #endif
30 
31  // initialise the EPM to the neutral position
32  neutral();
33 }
34 
35 // Refer to http://uavcan.org/Specification/7._List_of_standard_data_types/#uavcanequipmenthardpoint
36 struct UAVCANCommand {
37  uint8_t hardpoint_id = 0;
38  uint16_t command = 0;
39 };
40 
41 // grab - move the epm pwm output to the grab position
43 {
44  // flag we are active and grabbing cargo
46 
47  // capture time
49 
50 #ifdef UAVCAN_IOCS_HARDPOINT_SET
51  if (should_use_uavcan()) {
52  const UAVCANCommand cmd = make_uavcan_command(1);
53  (void)ioctl(_uavcan_fd, UAVCAN_IOCS_HARDPOINT_SET, reinterpret_cast<unsigned long>(&cmd));
54  }
55  else
56 #endif
57  {
58  // move the servo output to the grab position
60  }
61 }
62 
63 // release - move epm pwm output to the release position
65 {
66  // flag we are releasing cargo
68 
69  // capture time
71 
72 #ifdef UAVCAN_IOCS_HARDPOINT_SET
73  if (should_use_uavcan()) {
74  const UAVCANCommand cmd = make_uavcan_command(0);
75  (void)ioctl(_uavcan_fd, UAVCAN_IOCS_HARDPOINT_SET, reinterpret_cast<unsigned long>(&cmd));
76  }
77  else
78 #endif
79  {
80  // move the servo to the release position
82  }
83 }
84 
85 // neutral - return the epm pwm output to the neutral position
87 {
88  if (!should_use_uavcan()) {
89  // move the servo to the off position
91  }
92 }
93 
94 // update - moves the pwm back to neutral after the timeout has passed
95 // should be called at at least 10hz
97 {
98  // move EPM PWM output back to neutral after the last grab or release
101  neutral();
103  } else if (config.state == AP_Gripper::STATE_RELEASING) {
104  neutral();
106  }
107  }
108 
109  // re-grab the cargo intermittently
111  (config.regrab_interval > 0) &&
112  (AP_HAL::millis() - _last_grab_or_release > ((uint32_t)config.regrab_interval * 1000))) {
113  grab();
114  }
115 }
116 
118 {
119  UAVCANCommand cmd;
121  cmd.command = command;
122  return cmd;
123 }
124 
125 
127 {
128  // we assume instanteous releasing ATM:
131 }
132 
134 {
135  // we assume instanteous grabbing ATM:
138 }
int printf(const char *fmt,...)
Definition: stdio.c:113
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
bool grabbed() const override
void update_gripper() override
uint32_t _last_grab_or_release
#define EPM_RETURN_TO_NEUTRAL_MS
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
uint32_t millis()
Definition: system.cpp:157
void grab() override
struct UAVCANCommand make_uavcan_command(uint16_t command) const
bool released() const override
void release() override
AP_Gripper_EPM(struct AP_Gripper::Backend_Config &_config)
struct AP_Gripper::Backend_Config & config
bool should_use_uavcan() const
uint8_t hardpoint_id
void init_gripper() override