Protocol.cpp
Go to the documentation of this file.
1 /*
2 BSD 2-Clause License
3 
4 Copyright (c) 2019, Simranjeet Singh
5 All rights reserved.
6 
7 Redistribution and use in source and binary forms, with or without
8 modification, are permitted provided that the following conditions are met:
9 
10 1. Redistributions of source code must retain the above copyright notice, this
11  list of conditions and the following disclaimer.
12 
13 2. Redistributions in binary form must reproduce the above copyright notice,
14  this list of conditions and the following disclaimer in the documentation
15  and/or other materials provided with the distribution.
16 
17 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
21 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
25 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 */
28 
29 #include <unistd.h>
30 #include <eyantra_drone/Protocol.h>
31 #include <string>
32 
33 std::string MSP_HEADER="$M<";
34 
35 int8_t inputBuffer[1024];
36 uint8_t bufferIndex=0;
37 //NSMutableArray* requests;
38 
39 
40 int roll=0;
41 int pitch=0;
42 int yaw=0;
43 float battery=0;
44 int rssi=0;
45 float accX=0;
46 float accY=0;
47 float accZ=0;
48 float gyroX=0;
49 float gyroY=0;
50 float gyroZ=0;
51 float magX=0;
52 float magY=0;
53 float magZ=0;
54 float alt=0;
55 
59 
60 int trim_roll=0;
61 int trim_pitch=0;
62 
63 float rcThrottle = 1500, rcRoll = 1500, rcPitch = 1500, rcYaw = 1500, rcAUX1 = 1500, rcAUX2 = 1500, rcAUX3 = 1500, rcAUX4 = 1500;
64 
66 {
67  return inputBuffer[bufferIndex++] & 0xff;
68 }
69 
71 {
72  int add_1=(inputBuffer[bufferIndex++] & 0xff) ;
73  int add_2=((inputBuffer[bufferIndex++]) << 8);
74 
75  return add_1+add_2;
76 }
77 
79 {
80  return (inputBuffer[bufferIndex++] & 0xff) + ((inputBuffer[bufferIndex++] & 0xff) << 8)
81  + ((inputBuffer[bufferIndex++] & 0xff) << 16) + ((inputBuffer[bufferIndex++] & 0xff) << 24);
82 }
83 
85 {
86  switch (command) {
87 
88  case MSP_FC_VERSION:
92 
93  break;
94 
95  case MSP_RAW_IMU:
96 
97  accX=read16();
98  accY=read16();
99  accZ=read16();
100 
101  gyroX=read16()/8;
102  gyroY=read16()/8;
103  gyroZ=read16()/8;
104 
105  magX=read16()/3;
106  magY=read16()/3;
107  magZ=read16()/3;
108 
109  break;
110 
111  case MSP_ATTITUDE:
112  //for(int i=0; i<6;i++)
113  //NSLog(@"value of %i",inputBuffer[i]);
114  roll=(read16()/10);
115  pitch=(read16()/10);
116  yaw=read16();
117 
118  break;
119 
120  case MSP_ALTITUDE:
121  alt=(read32()/10)-0;
122 
123  break;
124 
125  case MSP_ANALOG:
126 
127  battery=(read8()/10.0);
128  rssi=read16();
129 
130  break;
131 
132  case MSP_ACC_TRIM:
133 
134  trim_pitch=read16();
135  trim_roll=read16();
136 
137  break;
138 
139  case MSP_RC:
140 
141  rcRoll = read16();
142  rcPitch = read16();
143  rcYaw = read16();
144  rcThrottle = read16();
145  rcAUX1 = read16();
146  rcAUX2 = read16();
147  rcAUX3 = read16();
148  rcAUX4 = read16();
149 
150  break;
151 
152  default:
153  break;
154  }
155 }
156 
157 void Protocol::sendRequestMSP(std::vector<int8_t> data)
158 {
159  com.writeSock(&data[0],data.size());
160 }
161 
162 void Protocol::sendMulRequestMSP(std::vector<int8_t> data, int i)
163 {
164  com.writeMulSock(&data[0],data.size(),i);
165 }
166 
167 std::vector<int8_t> Protocol::createPacketMSP(int msp, std::vector<int8_t>payload)
168 {
169  if (msp < 0) {
170  //return NULL;
171  }
172  std::vector<int8_t> bf;
173  for(std::string::iterator it = MSP_HEADER.begin(); it != MSP_HEADER.end(); ++it) {
174  bf.push_back((int8_t) (*it & 0xFF));
175  }
176  int8_t checksum = 0;
177  int8_t pl_size = (int8_t) ((!payload.empty() ? (int) (payload.size()) : 0) & 0xFF);
178  bf.push_back(pl_size);
179  checksum ^= (pl_size & 0xFF);
180 
181  bf.push_back((int8_t) (msp & 0xFF));
182  checksum ^= (msp & 0xFF);
183 
184  if (!payload.empty()) {
185  //printf("Adding payload %d\n");
186  for (std::vector<int8_t>::iterator it = payload.begin() ; it != payload.end(); ++it) {
187  int8_t k=*it;
188  //printf("payload value %i\n",k);
189  bf.push_back((int8_t) (k & 0xFF));
190  checksum ^= (k & 0xFF);
191  }
192  }
193  bf.push_back(checksum);
194  return (bf);
195 }
196 
198 {
199  std::vector<int8_t>rc_signals(16);
200  int index = 0;
201  for (int i = 0; i < 8; i++) {
202  //Log.d("drona", "Data: " + (channels8[i]));
203  rc_signals[index++] = (int8_t) (channels[i] & 0xFF);
204  rc_signals[index++] = (int8_t) ((channels[i] >> 8) & 0xFF);
205  //printf("rcvalue = %i\n" ,channels[i]);
206  //rc_signals.push_back((uint8_t) (channels[i] & 0xFF));
207  //rc_signals.push_back( (uint8_t) ((channels[i] >> 8) & 0xFF));
208  }
209  //printf("size of rc_array %d\n",rc_signals.size() );
211 }
212 
214 {
215  std::vector<int8_t>rc_signals(16);
216  int index = 0;
217  int droneNumber = channels[8];
218  for (int i = 0; i < 8; i++) {
219  //Log.d("drona", "Data: " + (channels8[i]));
220  rc_signals[index++] = (int8_t) (channels[i] & 0xFF);
221  rc_signals[index++] = (int8_t) ((channels[i] >> 8) & 0xFF);
222  //printf("rcvalue = %i\n" ,channels[i]);
223  //rc_signals.push_back((uint8_t) (channels[i] & 0xFF));
224  //rc_signals.push_back( (uint8_t) ((channels[i] >> 8) & 0xFF));
225  }
226  //printf("size of rc_array %d\n",rc_signals.size() );
227  sendMulRequestMSP(createPacketMSP(MSP_SET_RAW_RC, rc_signals), droneNumber);
228 }
229 
231 {
232  std::vector<int8_t>posData(8);
233  int index = 0;
234  for (int i = 0; i < 4; i++) {
235  //Log.d("drona", "Data: " + (channels8[i]));
236  posData[index++] = (int8_t) (posArray[i] & 0xFF);
237  posData[index++] = (int8_t) ((posArray[i] >> 8) & 0xFF);
238 
239  // printf("posvalue = %i\n" ,posArray[i]);
240  // rc_signals.push_back((uint8_t) (channels[i] & 0xFF));
241  //rc_signals.push_back( (uint8_t) ((channels[i] >> 8) & 0xFF));
242  }
244 }
245 
246 void Protocol::sendRequestMSP_GET_DEBUG(std::vector<int> requests)
247 {
248  for (size_t i = 0; i < requests.size(); i++) {
249 
250  sendRequestMSP(createPacketMSP(requests[i], std::vector<int8_t>()));
251 
252  }
253 }
254 
255 void Protocol::sendMulRequestMSP_GET_DEBUG(std::vector<int> requests, int index)
256 {
257  for (size_t i = 0; i < requests.size(); i++) {
258 
259  sendMulRequestMSP(createPacketMSP(requests[i], std::vector<int8_t>()), index);
260 
261  }
262 }
float rcAUX2
Definition: Protocol.cpp:63
int8_t inputBuffer[1024]
Definition: Protocol.cpp:35
static const int MSP_ATTITUDE
Definition: Protocol.h:43
int i
float rcRoll
Definition: Protocol.cpp:63
int yaw
Definition: Protocol.cpp:42
uint8_t command
float rcPitch
Definition: Protocol.cpp:63
float alt
Definition: Protocol.cpp:54
float gyroY
Definition: Protocol.cpp:49
void sendMulRequestMSP_SET_RAW_RC(int channels[])
Definition: Protocol.cpp:213
float battery
Definition: Protocol.cpp:43
uint8_t checksum
float gyroX
Definition: Protocol.cpp:48
float magY
Definition: Protocol.cpp:52
int FC_versionMajor
Definition: Protocol.cpp:56
float rcAUX4
Definition: Protocol.cpp:63
float rcThrottle
Definition: Protocol.cpp:63
static const int MSP_FC_VERSION
Definition: Protocol.h:40
float rcAUX1
Definition: Protocol.cpp:63
void sendRequestMSP(std::vector< int8_t > data)
Definition: Protocol.cpp:157
std::string MSP_HEADER
Definition: Protocol.cpp:33
static const int MSP_SET_POS
Definition: Protocol.h:53
static const int MSP_RC
Definition: Protocol.h:42
float magX
Definition: Protocol.cpp:51
int rssi
Definition: Protocol.cpp:44
void sendRequestMSP_GET_DEBUG(std::vector< int > requests)
Definition: Protocol.cpp:246
float rcYaw
Definition: Protocol.cpp:63
int writeMulSock(const void *buf, int count, int i)
static const int MSP_ALTITUDE
Definition: Protocol.h:44
float accZ
Definition: Protocol.cpp:47
Communication com
Definition: DroneNode.cpp:49
int trim_pitch
Definition: Protocol.cpp:61
float magZ
Definition: Protocol.cpp:53
static const int MSP_ACC_TRIM
Definition: Protocol.h:51
float accY
Definition: Protocol.cpp:46
int writeSock(const void *buf, int count)
void evaluateCommand(int command)
Definition: Protocol.cpp:84
float gyroZ
Definition: Protocol.cpp:50
int read16()
Definition: Protocol.cpp:70
void sendMulRequestMSP_GET_DEBUG(std::vector< int > requests, int index)
Definition: Protocol.cpp:255
int read32()
Definition: Protocol.cpp:78
int FC_versionMinor
Definition: Protocol.cpp:57
std::vector< int8_t > createPacketMSP(int msp, std::vector< int8_t >payload)
Definition: Protocol.cpp:167
void sendRequestMSP_SET_POS(int posArray[])
Definition: Protocol.cpp:230
static const int MSP_ANALOG
Definition: Protocol.h:45
int roll
Definition: Protocol.cpp:40
int trim_roll
Definition: Protocol.cpp:60
void sendMulRequestMSP(std::vector< int8_t > data, int i)
Definition: Protocol.cpp:162
float accX
Definition: Protocol.cpp:45
static const int MSP_SET_RAW_RC
Definition: Protocol.h:46
float rcAUX3
Definition: Protocol.cpp:63
static const int MSP_RAW_IMU
Definition: Protocol.h:41
int read8()
Definition: Protocol.cpp:65
void sendRequestMSP_SET_RAW_RC(int channels[])
Definition: Protocol.cpp:197
uint8_t bufferIndex
Definition: Protocol.cpp:36
int FC_versionPatchLevel
Definition: Protocol.cpp:58
int pitch
Definition: Protocol.cpp:41


edrone_client
Author(s): Simranjeet Singh
autogenerated on Sun Dec 1 2019 03:30:51