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.000583};
70  double trackWidth{1.63576};
71  double odometerVelocityCovariance{0.00001};
72  bool encoderOnLeft{true};
73  };
74 
83  class Driver
84  {
85  private:
86  bool connected_;
87  std::string port_;
88  const uint32_t PACKET_PERIOD{50};
91  bool debug_{false};
92  std::vector<packet_id_e> packetRequests_;
98 
99  // Private functions, see implementation for detailed comments
100  int DecodePacket(an_packet_t *);
101  int DecodeUtmFix(utm_fix *, an_packet_t *); // Special decode since their utm api is incorrect
102  int SendPacket(an_packet_t *);
103 
104  public:
105  explicit Driver(bool _debug = false);
106  ~Driver();
107 
116  int Init(const std::string &_port, KvhPacketRequest &_packetsRequested);
117 
129  int Init(const std::string &_port, KvhPacketRequest &_packetsRequested, KvhInitOptions _initOptions);
130 
146  int Once();
147 
159 
165  int SetPacketUpdated(packet_id_e, bool);
166 
172  int AddPacket(packet_id_e);
173 
189  template <class T>
190  int GetPacket(packet_id_e _packetId, T &_packet)
191  {
192  return packetStorage_.GetPacket(_packetId, _packet);
193  }
194 
202 
210  int Cleanup();
211 
212  }; //end: class Driver
213 
214 } // namespace kvh
kvh::Driver::connected_
bool connected_
True if we're connected to the localization unit.
Definition: kvh_geo_fog_3d_driver.hpp:86
kvh::Driver::DecodeUtmFix
int DecodeUtmFix(utm_fix *, an_packet_t *)
The current api given by kvh incorrectly deals with this packet so we needed to write our own decoder...
Definition: decode_packets.cpp:54
kvh::KvhInitOptions::debugOn
bool debugOn
Definition: kvh_geo_fog_3d_driver.hpp:63
kvh::KvhInitOptions::reversingDetectionEnabled
bool reversingDetectionEnabled
Definition: kvh_geo_fog_3d_driver.hpp:67
kvh::KvhInitOptions::gnssEnabled
bool gnssEnabled
Definition: kvh_geo_fog_3d_driver.hpp:60
kvh::Driver::RequestPacket
int RequestPacket(packet_id_e)
This function is used to request packets that you only want once or that cannot be requested through ...
Definition: driver_main.cpp:376
an_packet_t
Definition: an_packet_protocol.h:61
rs232.h
kvh::KvhPacketRequest
std::vector< std::pair< packet_id_e, uint16_t > > KvhPacketRequest
Definition: kvh_geo_fog_3d_packet_storage.hpp:65
kvh::KvhInitOptions
Definition: kvh_geo_fog_3d_driver.hpp:58
kvh_geo_fog_3d_device_configuration.hpp
Helper functions for configuring the hardware.
kvh::Driver::PACKET_PERIOD
const uint32_t PACKET_PERIOD
equal packet frequency. See manual for equation on how Packet Period affects packet rate.
Definition: kvh_geo_fog_3d_driver.hpp:88
vehicle_type_car
@ vehicle_type_car
Definition: spatial_packets.h:808
kvh::KvhInitOptions::atmosphericAltitudeEnabled
bool atmosphericAltitudeEnabled
Definition: kvh_geo_fog_3d_driver.hpp:65
kvh::Driver::SendPacket
int SendPacket(an_packet_t *)
Wrapper function for more easily sending an packets via serial port.
Definition: driver_main.cpp:86
kvh
Definition: kvh_geo_fog_3d_device_configuration.hpp:44
kvh::KvhInitOptions::port
std::string port
Definition: kvh_geo_fog_3d_driver.hpp:62
an_packet_protocol.h
kvh::KvhInitOptions::velocityHeadingEnabled
bool velocityHeadingEnabled
Definition: kvh_geo_fog_3d_driver.hpp:66
kvh::KvhInitOptions::odomPulseToMeters
double odomPulseToMeters
Definition: kvh_geo_fog_3d_driver.hpp:69
kvh::Driver
Driver worker class for the KVH Geo Fog 3D.
Definition: kvh_geo_fog_3d_driver.hpp:83
kvh_geo_fog_3d_global_vars.hpp
global variables used to store packet information.
kvh::Driver::defaultOptions_
KvhInitOptions defaultOptions_
If no init options are passed in, use this as the default.
Definition: kvh_geo_fog_3d_driver.hpp:95
kvh::KvhPacketStorage
Definition: kvh_geo_fog_3d_packet_storage.hpp:67
kvh::Driver::debug_
bool debug_
Set true to print debug statements.
Definition: kvh_geo_fog_3d_driver.hpp:91
kvh::KvhInitOptions::trackWidth
double trackWidth
Definition: kvh_geo_fog_3d_driver.hpp:70
kvh::Driver::packetStorage_
KvhPacketStorage packetStorage_
Class responsible for handling packets and ensuring consistency.
Definition: kvh_geo_fog_3d_driver.hpp:96
kvh::Driver::anDecoder_
an_decoder_t anDecoder_
Decoder for decoding incoming AN encoded packets.
Definition: kvh_geo_fog_3d_driver.hpp:90
kvh::utm_fix
Definition: kvh_geo_fog_3d_global_vars.hpp:51
an_decoder_t
Definition: an_packet_protocol.h:54
kvh::Driver::AddPacket
int AddPacket(packet_id_e)
Definition: driver_main.cpp:358
kvh::Driver::~Driver
~Driver()
Destructor. Will automatically cleanup the driver.
Definition: driver_main.cpp:71
kvh::KvhInitOptions::odometerVelocityCovariance
double odometerVelocityCovariance
Definition: kvh_geo_fog_3d_driver.hpp:71
kvh::KvhInitOptions::filterVehicleType
uint8_t filterVehicleType
Definition: kvh_geo_fog_3d_driver.hpp:64
kvh::Driver::packetRequests_
std::vector< packet_id_e > packetRequests_
Definition: kvh_geo_fog_3d_driver.hpp:92
kvh_geo_fog_3d_packet_storage.hpp
KVH Packet storing class header.
kvh::Driver::PacketIsUpdated
bool PacketIsUpdated(packet_id_e)
Use this function to determine if new packet data has arrived since the last time you checked.
Definition: driver_main.cpp:334
kvh::KvhInitOptions::baudRate
int baudRate
Definition: kvh_geo_fog_3d_driver.hpp:61
kvh::KvhInitOptions::encoderOnLeft
bool encoderOnLeft
Definition: kvh_geo_fog_3d_driver.hpp:72
kvh::Driver::Driver
Driver(bool _debug=false)
Initializes connected status, port to use, and if debug printing is turned on.
Definition: driver_main.cpp:61
packet_id_e
packet_id_e
Definition: spatial_packets.h:45
kvh::Driver::DecodePacket
int DecodePacket(an_packet_t *)
Definition: decode_packets.cpp:79
kvh::Driver::GetPacket
int GetPacket(packet_id_e _packetId, T &_packet)
Retrieves the requested packets that are currently stored. Use PacketIsUpdated and SetPacketUpdated t...
Definition: kvh_geo_fog_3d_driver.hpp:190
kvh::KvhPacketStorage::GetPacket
int GetPacket(packet_id_e _packetId, T &_packet)
Definition: kvh_geo_fog_3d_packet_storage.hpp:151
kvh::Driver::Once
int Once()
Do a single data read from the device.
Definition: driver_main.cpp:276
kvh::Driver::Cleanup
int Cleanup()
Cleanup and close our connections.
Definition: driver_main.cpp:394
kvh::Driver::SetPacketUpdated
int SetPacketUpdated(packet_id_e, bool)
Use this function to set that the packet has been updated (though the driver will usually do that its...
Definition: driver_main.cpp:348
kvh::KvhInitOptions::motionAnalysisEnabled
bool motionAnalysisEnabled
Definition: kvh_geo_fog_3d_driver.hpp:68
kvh::Driver::Init
int Init(const std::string &_port, KvhPacketRequest &_packetsRequested)
Definition: driver_main.cpp:115
spatial_packets.h
kvh::Driver::deviceConfig_
KvhDeviceConfig deviceConfig_
Class responsible for configuring kvh geo fog.
Definition: kvh_geo_fog_3d_driver.hpp:97
kvh::Driver::port_
std::string port_
Port to connect to the kvh through. Ex. "/dev/ttyUSB0".
Definition: kvh_geo_fog_3d_driver.hpp:87
kvh::KvhDeviceConfig
Definition: kvh_geo_fog_3d_device_configuration.hpp:47


kvh_geo_fog_3d_driver
Author(s): Trevor Bostic , Zach LaCelle
autogenerated on Wed Mar 2 2022 00:28:57