kvh_geo_fog_3d_driver.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (Apache 2.0)
3  *
4  * Copyright (c) 2019, The MITRE Corporation.
5  * All rights reserved.
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  *
11  * https://www.apache.org/licenses/LICENSE-2.0
12  *
13  * Unless required by applicable law or agreed to in writing, software
14  * distributed under the License is distributed on an "AS IS" BASIS,
15  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16  * See the License for the specific language governing permissions and
17  * limitations under the License.
18  *
19  * Sections of this project contains content developed by The MITRE Corporation.
20  * If this code is used in a deployment or embedded within another project,
21  * it is requested that you send an email to opensource@mitre.org in order to
22  * let us know where this software is being used.
23  *********************************************************************/
24 
32 #pragma once
33 
34 // STD
35 #include <vector>
36 #include <set>
37 #include <map>
38 #include <memory>
39 #include <functional>
40 #include <iostream>
41 
42 // GEO-FOG SDK
43 #include "rs232.h"
44 #include "an_packet_protocol.h"
45 #include "spatial_packets.h"
46 
47 // Kvh Driver Components
51 
52 namespace kvh
53 {
59  {
60  bool gnssEnabled{true};
61  int baudRate{115200};
62  std::string port{"/tty/USB0"};
63  bool debugOn{false};
69  double odomPulseToMeters{0.000604};
70  };
71 
80  class Driver
81  {
82  private:
83  bool connected_;
84  std::string port_;
85  const uint32_t PACKET_PERIOD{50};
86  an_decoder_t anDecoder_;
88  bool debug_{false};
89  std::vector<packet_id_e> packetRequests_;
90  KvhInitOptions defaultOptions_;
95 
96  // Private functions, see implementation for detailed comments
97  int DecodePacket(an_packet_t *);
98  int DecodeUtmFix(utm_fix *, an_packet_t *); // Special decode since their utm api is incorrect
99  int SendPacket(an_packet_t *);
100 
101  public:
102  explicit Driver(bool _debug = false);
103  ~Driver();
104 
113  int Init(const std::string &_port, KvhPacketRequest &_packetsRequested);
114 
126  int Init(const std::string &_port, KvhPacketRequest &_packetsRequested, KvhInitOptions _initOptions);
127 
143  int Once();
144 
145  bool PacketIsUpdated(packet_id_e);
146  int SetPacketUpdated(packet_id_e, bool);
147 
148  template <class T>
149  int GetPacket(packet_id_e _packetId, T &packet)
150  {
151  return packetStorage_.GetPacket(_packetId, packet);
152  }
153 
161  int Cleanup();
162 
163  }; //end: class Driver
164 
165 } // namespace kvh
std::string port_
Port to connect to the kvh through. Ex. "/dev/ttyUSB0".
Driver worker class for the KVH Geo Fog 3D.
global variables used to store packet information.
Helper functions for configuring the hardware.
bool connected_
True if we&#39;re connected to the localization unit.
int GetPacket(packet_id_e _packetId, T &packet)
packet_id_e
KVH Packet storing class header.
std::vector< packet_id_e > packetRequests_
std::vector< std::pair< packet_id_e, uint16_t > > KvhPacketRequest
int GetPacket(packet_id_e _packetId, T &_packet)
KvhPacketStorage packetStorage_
Class responsible for handling packets and ensuring consistency.
KvhDeviceConfig deviceConfig_
Class responsible for configuring kvh geo fog.


kvh_geo_fog_3d_driver
Author(s): Trevor Bostic , Zach LaCelle
autogenerated on Fri Jan 24 2020 03:18:17