vesc_packet.h
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 
28 #ifndef VESC_DRIVER_VESC_PACKET_H_
29 #define VESC_DRIVER_VESC_PACKET_H_
30 
31 #include <cstdint>
32 #include <memory>
33 #include <string>
34 #include <vector>
35 #include <utility>
36 
37 #define CRCPP_USE_CPP11
38 #include "vesc_driver/crc.h"
39 
40 namespace vesc_driver
41 {
42 
43 typedef std::vector<uint8_t> Buffer;
44 typedef std::pair<Buffer::iterator, Buffer::iterator> BufferRange;
45 typedef std::pair<Buffer::const_iterator, Buffer::const_iterator> BufferRangeConst;
46 
48 class VescFrame
49 {
50 public:
51  virtual ~VescFrame() {}
52 
53  // getters
54  virtual const Buffer& frame() const
55  {
56  return *frame_;
57  }
58 
59  // VESC packet properties
60  static const int VESC_MAX_PAYLOAD_SIZE = 1024;
61  static const int VESC_MIN_FRAME_SIZE = 5;
62  static const int VESC_MAX_FRAME_SIZE = 6 + VESC_MAX_PAYLOAD_SIZE;
63  static const unsigned int VESC_SOF_VAL_SMALL_FRAME = 2;
64  static const unsigned int VESC_SOF_VAL_LARGE_FRAME = 3;
65  static const unsigned int VESC_EOF_VAL = 3;
66 
68  static constexpr CRC::Parameters<crcpp_uint16, 16> CRC_TYPE = { 0x1021, 0x0000, 0x0000, false, false };
69 
70 protected:
72  explicit VescFrame(int payload_size);
73 
74  std::shared_ptr<Buffer> frame_;
75  BufferRange payload_;
76 
77 private:
79  VescFrame(const BufferRangeConst& frame, const BufferRangeConst& payload);
80 
82  friend class VescPacketFactory;
83 };
84 
85 /*------------------------------------------------------------------------------------------------*/
86 
88 class VescPacket : public VescFrame
89 {
90 public:
91  virtual ~VescPacket() {}
92 
93  virtual const std::string& name() const
94  {
95  return name_;
96  }
97 
98 protected:
99  VescPacket(const std::string& name, int payload_size, int payload_id);
100  VescPacket(const std::string& name, std::shared_ptr<VescFrame> raw);
101 
102 private:
103  std::string name_;
104 };
105 
106 typedef std::shared_ptr<VescPacket> VescPacketPtr;
107 typedef std::shared_ptr<VescPacket const> VescPacketConstPtr;
108 
109 /*------------------------------------------------------------------------------------------------*/
110 
112 {
113 public:
114  explicit VescPacketFWVersion(std::shared_ptr<VescFrame> raw);
115 
116  int fwMajor() const;
117  int fwMinor() const;
118 };
119 
121 {
122 public:
124 };
125 
126 /*------------------------------------------------------------------------------------------------*/
127 
129 {
130 public:
131  explicit VescPacketValues(std::shared_ptr<VescFrame> raw);
132 
133  double v_in() const;
134  double temp_mos1() const;
135  double temp_mos2() const;
136  double temp_mos3() const;
137  double temp_mos4() const;
138  double temp_mos5() const;
139  double temp_mos6() const;
140  double temp_pcb() const;
141  double current_motor() const;
142  double current_in() const;
143  double rpm() const;
144  double duty_now() const;
145  double amp_hours() const;
146  double amp_hours_charged() const;
147  double watt_hours() const;
148  double watt_hours_charged() const;
149  double tachometer() const;
150  double tachometer_abs() const;
151  int fault_code() const;
152 };
153 
155 {
156 public:
158 };
159 
160 /*------------------------------------------------------------------------------------------------*/
161 
163 {
164 public:
165  explicit VescPacketSetDuty(double duty);
166 
167  // double duty() const;
168 };
169 
170 /*------------------------------------------------------------------------------------------------*/
171 
173 {
174 public:
175  explicit VescPacketSetCurrent(double current);
176 
177  // double current() const;
178 };
179 
180 /*------------------------------------------------------------------------------------------------*/
181 
183 {
184 public:
185  explicit VescPacketSetCurrentBrake(double current_brake);
186 
187  // double current_brake() const;
188 };
189 
190 /*------------------------------------------------------------------------------------------------*/
191 
193 {
194 public:
195  explicit VescPacketSetRPM(double rpm);
196 
197  // double rpm() const;
198 };
199 
200 /*------------------------------------------------------------------------------------------------*/
201 
203 {
204 public:
205  explicit VescPacketSetPos(double pos);
206 
207  // double pos() const;
208 };
209 
210 /*------------------------------------------------------------------------------------------------*/
211 
213 {
214 public:
215  explicit VescPacketSetServoPos(double servo_pos);
216 
217  // double servo_pos() const;
218 };
219 
220 } // namespace vesc_driver
221 
222 #endif // VESC_DRIVER_VESC_PACKET_H_
std::pair< Buffer::iterator, Buffer::iterator > BufferRange
Definition: vesc_packet.h:44
static constexpr CRC::Parameters< crcpp_uint16, 16 > CRC_TYPE
Definition: vesc_packet.h:68
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
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
static const int VESC_MAX_PAYLOAD_SIZE
Maximum VESC payload size, in bytes.
Definition: vesc_packet.h:60
static const unsigned int VESC_EOF_VAL
VESC end-of-frame value.
Definition: vesc_packet.h:65
std::shared_ptr< VescPacket > VescPacketPtr
Definition: vesc_packet.h:106
std::shared_ptr< VescPacket const > VescPacketConstPtr
Definition: vesc_packet.h:107
static const unsigned int VESC_SOF_VAL_LARGE_FRAME
VESC start of "large" frame value.
Definition: vesc_packet.h:64
static const unsigned int VESC_SOF_VAL_SMALL_FRAME
VESC start of "small" frame value.
Definition: vesc_packet.h:63
BufferRange payload_
View into frame&#39;s payload section.
Definition: vesc_packet.h:75


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