vesc_packet.cpp
Go to the documentation of this file.
1 // Copyright 2020 F1TENTH Foundation
2 //
3 // Redistribution and use in source and binary forms, with or without modification, are permitted
4 // provided that the following conditions are met:
5 //
6 // 1. Redistributions of source code must retain the above copyright notice, this list of conditions
7 // and the following disclaimer.
8 //
9 // 2. Redistributions in binary form must reproduce the above copyright notice, this list
10 // of conditions and the following disclaimer in the documentation and/or other materials
11 // provided with the distribution.
12 //
13 // 3. Neither the name of the copyright holder nor the names of its contributors may be used
14 // to endorse or promote products derived from this software without specific prior
15 // written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
18 // IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
19 // FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
20 // CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
21 // DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
22 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
23 // WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY
24 // WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 
26 // -*- mode:c++; fill-column: 100; -*-
27 
29 
30 #include <cassert>
31 #include <iterator>
32 #include <memory>
33 #include <string>
34 
36 #include "vesc_driver/datatypes.h"
37 
38 namespace vesc_driver
39 {
40 
42 
43 VescFrame::VescFrame(int payload_size)
44 {
45  assert(payload_size >= 0 && payload_size <= 1024);
46 
47  if (payload_size < 256)
48  {
49  // single byte payload size
50  frame_.reset(new Buffer(VESC_MIN_FRAME_SIZE + payload_size));
51  *frame_->begin() = 2;
52  *(frame_->begin() + 1) = payload_size;
53  payload_.first = frame_->begin() + 2;
54  }
55  else
56  {
57  // two byte payload size
58  frame_.reset(new Buffer(VESC_MIN_FRAME_SIZE + 1 + payload_size));
59  *frame_->begin() = 3;
60  *(frame_->begin() + 1) = payload_size >> 8;
61  *(frame_->begin() + 2) = payload_size & 0xFF;
62  payload_.first = frame_->begin() + 3;
63  }
64 
65  payload_.second = payload_.first + payload_size;
66  *(frame_->end() - 1) = 3;
67 }
68 
70 {
71  /* VescPacketFactory::createPacket() should make sure that the input is valid, but run a few cheap
72  checks anyway */
73  assert(std::distance(frame.first, frame.second) >= VESC_MIN_FRAME_SIZE);
74  assert(std::distance(frame.first, frame.second) <= VESC_MAX_FRAME_SIZE);
75  assert(std::distance(payload.first, payload.second) <= VESC_MAX_PAYLOAD_SIZE);
76  assert(std::distance(frame.first, payload.first) > 0 &&
77  std::distance(payload.second, frame.second) > 0);
78 
79  frame_.reset(new Buffer(frame.first, frame.second));
80  payload_.first = frame_->begin() + std::distance(frame.first, payload.first);
81  payload_.second = frame_->begin() + std::distance(frame.first, payload.second);
82 }
83 
84 VescPacket::VescPacket(const std::string& name, int payload_size, int payload_id) :
85  VescFrame(payload_size), name_(name)
86 {
87  assert(payload_id >= 0 && payload_id < 256);
88  assert(std::distance(payload_.first, payload_.second) > 0);
89  *payload_.first = payload_id;
90 }
91 
92 VescPacket::VescPacket(const std::string& name, std::shared_ptr<VescFrame> raw) :
93  VescFrame(*raw), name_(name)
94 {
95 }
96 
97 /*------------------------------------------------------------------------------------------------*/
98 
99 VescPacketFWVersion::VescPacketFWVersion(std::shared_ptr<VescFrame> raw) :
100  VescPacket("FWVersion", raw)
101 {
102 }
103 
105 {
106  return *(payload_.first + 1);
107 }
108 
110 {
111  return *(payload_.first + 2);
112 }
113 
115 
117  VescPacket("RequestFWVersion", 1, COMM_FW_VERSION)
118 {
119  uint16_t crc = CRC::Calculate(
120  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
121  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
122  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
123 }
124 
125 /*------------------------------------------------------------------------------------------------*/
126 
127 VescPacketValues::VescPacketValues(std::shared_ptr<VescFrame> raw) :
128  VescPacket("Values", raw)
129 {
130 }
131 
133 {
134  int16_t v = static_cast<int16_t>((static_cast<uint16_t>(*(payload_.first + 1)) << 8) +
135  static_cast<uint16_t>(*(payload_.first + 2)));
136  return static_cast<double>(v) / 10.0;
137 }
138 
140 {
141  int16_t v = static_cast<int16_t>((static_cast<uint16_t>(*(payload_.first + 3)) << 8) +
142  static_cast<uint16_t>(*(payload_.first + 4)));
143  return static_cast<double>(v) / 10.0;
144 }
145 
147 {
148  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 5)) << 24) +
149  (static_cast<uint32_t>(*(payload_.first + 6)) << 16) +
150  (static_cast<uint32_t>(*(payload_.first + 7)) << 8) +
151  static_cast<uint32_t>(*(payload_.first + 8)));
152  return static_cast<double>(v) / 100.0;
153 }
154 
156 {
157  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 9)) << 24) +
158  (static_cast<uint32_t>(*(payload_.first + 10)) << 16) +
159  (static_cast<uint32_t>(*(payload_.first + 11)) << 8) +
160  static_cast<uint32_t>(*(payload_.first + 12)));
161  return static_cast<double>(v) / 100.0;
162 }
163 
164 
166 {
167  int16_t v = static_cast<int16_t>((static_cast<uint16_t>(*(payload_.first + 21)) << 8) +
168  static_cast<uint16_t>(*(payload_.first + 22)));
169  return static_cast<double>(v) / 1000.0;
170 }
171 
172 double VescPacketValues::rpm() const
173 {
174  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 23)) << 24) +
175  (static_cast<uint32_t>(*(payload_.first + 24)) << 16) +
176  (static_cast<uint32_t>(*(payload_.first + 25)) << 8) +
177  static_cast<uint32_t>(*(payload_.first + 26)));
178  return static_cast<double>(-1 * v);
179 }
180 
182 {
183  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 27)) << 24) +
184  (static_cast<uint32_t>(*(payload_.first + 28)) << 16) +
185  (static_cast<uint32_t>(*(payload_.first + 29)) << 8) +
186  static_cast<uint32_t>(*(payload_.first + 30)));
187  return static_cast<double>(v);
188 }
189 
191 {
192  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 31)) << 24) +
193  (static_cast<uint32_t>(*(payload_.first + 32)) << 16) +
194  (static_cast<uint32_t>(*(payload_.first + 33)) << 8) +
195  static_cast<uint32_t>(*(payload_.first + 34)));
196  return static_cast<double>(v);
197 }
198 
200 {
201  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 35)) << 24) +
202  (static_cast<uint32_t>(*(payload_.first + 36)) << 16) +
203  (static_cast<uint32_t>(*(payload_.first + 37)) << 8) +
204  static_cast<uint32_t>(*(payload_.first + 38)));
205  return static_cast<double>(v);
206 }
207 
209 {
210  int32_t v = static_cast<int32_t>((static_cast<uint32_t>(*(payload_.first + 39)) << 24) +
211  (static_cast<uint32_t>(*(payload_.first + 40)) << 16) +
212  (static_cast<uint32_t>(*(payload_.first + 41)) << 8) +
213  static_cast<uint32_t>(*(payload_.first + 42)));
214  return static_cast<double>(v);
215 }
216 
218 {
219  return static_cast<int32_t>(*(payload_.first + 56));
220 }
221 
223 {
224  int32_t v = 0;
225  return static_cast<double>(v);
226 }
227 
229 {
230  int32_t v = 0;
231  return static_cast<double>(v);
232 }
233 
235 {
236  int32_t v = 0;
237  return static_cast<double>(v);
238 }
239 
241 {
242  int32_t v = 0;
243  return static_cast<double>(v);
244 }
245 
247 
249  VescPacket("RequestValues", 1, COMM_GET_VALUES)
250 {
251  uint16_t crc = CRC::Calculate(
252  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
253  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
254  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
255 }
256 
257 /*------------------------------------------------------------------------------------------------*/
258 
259 
261  VescPacket("SetDuty", 5, COMM_SET_DUTY)
262 {
265  int32_t v = static_cast<int32_t>(duty * 100000.0);
266 
267  *(payload_.first + 1) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 24) & 0xFF);
268  *(payload_.first + 2) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 16) & 0xFF);
269  *(payload_.first + 3) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 8) & 0xFF);
270  *(payload_.first + 4) = static_cast<uint8_t>(static_cast<uint32_t>(v) & 0xFF);
271 
272  uint16_t crc = CRC::Calculate(
273  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
274  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
275  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
276 }
277 
278 /*------------------------------------------------------------------------------------------------*/
279 
281  VescPacket("SetCurrent", 5, COMM_SET_CURRENT)
282 {
283  int32_t v = static_cast<int32_t>(current * 1000.0);
284 
285  *(payload_.first + 1) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 24) & 0xFF);
286  *(payload_.first + 2) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 16) & 0xFF);
287  *(payload_.first + 3) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 8) & 0xFF);
288  *(payload_.first + 4) = static_cast<uint8_t>(static_cast<uint32_t>(v) & 0xFF);
289 
290  uint16_t crc = CRC::Calculate(
291  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
292  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
293  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
294 }
295 
296 /*------------------------------------------------------------------------------------------------*/
297 
299  VescPacket("SetCurrentBrake", 5, COMM_SET_CURRENT_BRAKE)
300 {
301  int32_t v = static_cast<int32_t>(current_brake * 1000.0);
302 
303  *(payload_.first + 1) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 24) & 0xFF);
304  *(payload_.first + 2) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 16) & 0xFF);
305  *(payload_.first + 3) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 8) & 0xFF);
306  *(payload_.first + 4) = static_cast<uint8_t>(static_cast<uint32_t>(v) & 0xFF);
307 
308  uint16_t crc = CRC::Calculate(
309  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
310  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
311  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
312 }
313 
314 /*------------------------------------------------------------------------------------------------*/
315 
317  VescPacket("SetRPM", 5, COMM_SET_RPM)
318 {
319  int32_t v = static_cast<int32_t>(rpm);
320 
321  *(payload_.first + 1) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 24) & 0xFF);
322  *(payload_.first + 2) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 16) & 0xFF);
323  *(payload_.first + 3) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 8) & 0xFF);
324  *(payload_.first + 4) = static_cast<uint8_t>(static_cast<uint32_t>(v) & 0xFF);
325 
326  uint16_t crc = CRC::Calculate(
327  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
328  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
329  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
330 }
331 
332 /*------------------------------------------------------------------------------------------------*/
333 
335  VescPacket("SetPos", 5, COMM_SET_POS)
336 {
339  int32_t v = static_cast<int32_t>(pos * 1000000.0);
340 
341  *(payload_.first + 1) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 24) & 0xFF);
342  *(payload_.first + 2) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 16) & 0xFF);
343  *(payload_.first + 3) = static_cast<uint8_t>((static_cast<uint32_t>(v) >> 8) & 0xFF);
344  *(payload_.first + 4) = static_cast<uint8_t>(static_cast<uint32_t>(v) & 0xFF);
345 
346  uint16_t crc = CRC::Calculate(
347  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
348  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
349  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
350 }
351 
352 /*------------------------------------------------------------------------------------------------*/
353 
355  VescPacket("SetServoPos", 3, COMM_SET_SERVO_POS)
356 {
359  int16_t v = static_cast<int16_t>(servo_pos * 1000.0);
360 
361  *(payload_.first + 1) = static_cast<uint8_t>((static_cast<uint16_t>(v) >> 8) & 0xFF);
362  *(payload_.first + 2) = static_cast<uint8_t>(static_cast<uint16_t>(v) & 0xFF);
363 
364  uint16_t crc = CRC::Calculate(
365  &(*payload_.first), std::distance(payload_.first, payload_.second), VescFrame::CRC_TYPE);
366  *(frame_->end() - 3) = static_cast<uint8_t>(crc >> 8);
367  *(frame_->end() - 2) = static_cast<uint8_t>(crc & 0xFF);
368 }
369 
370 } // namespace vesc_driver
static constexpr CRC::Parameters< crcpp_uint16, 16 > CRC_TYPE
Definition: vesc_packet.h:68
VescPacketSetServoPos(double servo_pos)
VescPacketFWVersion(std::shared_ptr< VescFrame > raw)
Definition: vesc_packet.cpp:99
std::vector< uint8_t > Buffer
Definition: vesc_packet.h:43
std::pair< Buffer::const_iterator, Buffer::const_iterator > BufferRangeConst
Definition: vesc_packet.h:45
VescFrame(int payload_size)
Definition: vesc_packet.cpp:43
std::shared_ptr< Buffer > frame_
Stores frame data, shared_ptr for shallow copy.
Definition: vesc_packet.h:74
virtual const Buffer & frame() const
Definition: vesc_packet.h:54
VescPacket(const std::string &name, int payload_size, int payload_id)
Definition: vesc_packet.cpp:84
static const int VESC_MIN_FRAME_SIZE
Smallest VESC frame size, in bytes.
Definition: vesc_packet.h:61
virtual const std::string & name() const
Definition: vesc_packet.h:93
static const int VESC_MAX_FRAME_SIZE
Largest VESC frame size, in bytes.
Definition: vesc_packet.h:62
#define REGISTER_PACKET_TYPE(id, klass)
static const int VESC_MAX_PAYLOAD_SIZE
Maximum VESC payload size, in bytes.
Definition: vesc_packet.h:60
double amp_hours_charged() const
static CRCType Calculate(const void *data, crcpp_size size, const Parameters< CRCType, CRCWidth > &parameters)
Computes a CRC.
Definition: crc.h:434
double watt_hours_charged() const
VescPacketValues(std::shared_ptr< VescFrame > raw)
BufferRange payload_
View into frame&#39;s payload section.
Definition: vesc_packet.h:75
VescPacketSetCurrentBrake(double current_brake)


vesc_driver
Author(s): Michael T. Boulet , Joshua Whitley
autogenerated on Sun Apr 18 2021 02:48:01