APM:Libraries
GCS_DeviceOp.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  handle device operations over MAVLink
17  */
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_HAL/Device.h>
20 #include <AP_HAL/I2CDevice.h>
21 #include "GCS.h"
22 #include <stdio.h>
23 
24 extern const AP_HAL::HAL& hal;
25 
26 /*
27  handle DEVICE_OP_READ message
28  */
29 void GCS_MAVLINK::handle_device_op_read(mavlink_message_t *msg)
30 {
31  mavlink_device_op_read_t packet;
32  mavlink_msg_device_op_read_decode(msg, &packet);
34  uint8_t retcode = 0;
35  uint8_t data[sizeof(mavlink_device_op_read_reply_t::data)] {};
36 
37  if (packet.bustype == DEVICE_OP_BUSTYPE_I2C) {
38  dev = hal.i2c_mgr->get_device(packet.bus, packet.address);
39  } else if (packet.bustype == DEVICE_OP_BUSTYPE_SPI) {
40  dev = hal.spi->get_device(packet.busname);
41  } else {
42  retcode = 1;
43  goto fail;
44  }
45  if (!dev) {
46  retcode = 2;
47  goto fail;
48  }
49  if (!dev->get_semaphore()->take(10)) {
50  retcode = 3;
51  goto fail;
52  }
53  if (!dev->read_registers(packet.regstart, data, packet.count)) {
54  retcode = 4;
55  dev->get_semaphore()->give();
56  goto fail;
57  }
58  dev->get_semaphore()->give();
59  mavlink_msg_device_op_read_reply_send(
60  chan,
61  packet.request_id,
62  retcode,
63  packet.regstart,
64  packet.count,
65  data);
66  return;
67 
68 fail:
69  mavlink_msg_device_op_read_reply_send(
70  chan,
71  packet.request_id,
72  retcode,
73  packet.regstart,
74  0,
75  nullptr);
76 }
77 
78 /*
79  handle DEVICE_OP_WRITE message
80  */
81 void GCS_MAVLINK::handle_device_op_write(mavlink_message_t *msg)
82 {
83  mavlink_device_op_write_t packet;
84  mavlink_msg_device_op_write_decode(msg, &packet);
86  uint8_t retcode = 0;
87 
88  if (packet.bustype == DEVICE_OP_BUSTYPE_I2C) {
89  dev = hal.i2c_mgr->get_device(packet.bus, packet.address);
90  } else if (packet.bustype == DEVICE_OP_BUSTYPE_SPI) {
91  dev = hal.spi->get_device(packet.busname);
92  } else {
93  retcode = 1;
94  goto fail;
95  }
96  if (!dev) {
97  retcode = 2;
98  goto fail;
99  }
100  if (!dev->get_semaphore()->take(10)) {
101  retcode = 3;
102  goto fail;
103  }
104  for (uint8_t i=0; i<packet.count; i++) {
105  if (!dev->write_register(packet.regstart+i, packet.data[i])) {
106  retcode = 4;
107  break;
108  }
109  }
110  dev->get_semaphore()->give();
111 
112 fail:
113  mavlink_msg_device_op_write_reply_send(
114  chan,
115  packet.request_id,
116  retcode);
117 }
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
Interface definition for the various Ground Control System.
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void fail(const char *why)
Definition: eedump.c:28
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
virtual bool give()=0
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125