kvh_geo_fog_3d_device_configuration.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 
31 #pragma once
32 
33 // STD
34 #include <stdint.h>
35 
36 // KVH Geo Fog
37 #include "an_packet_protocol.h"
38 #include "spatial_packets.h"
39 
40 // Driver
43 
44 namespace kvh
45 {
46 
48  {
49  private:
50  public:
62  static int CreatePacketPeriodsPacket(KvhPacketRequest &_packetsRequested, packet_periods_packet_t &_packetPeriods);
63 
72  static int CreateFilterOptionsPacket(
74  bool _permanent = true,
75  uint8_t _vehicle_type = vehicle_type_car,
76  bool _internal_gnss_enabled = true,
77  bool _atmospheric_altitude_enabled = true,
78  bool _velocity_heading_enabled = true,
79  bool _reversing_detection_enabled = true,
80  bool _motion_analysis_enabled = true);
81 
90  static int SetBaudRate(std::string _port, int _curBaudRate, int _primaryBaudRate, int _gpioBaudRate = 115200, int _auxBaudRate = 115200);
91 
98  static int FindCurrentBaudRate(std::string, int);
99 
109  };
110 
111 } // namespace kvh
static int SetBaudRate(std::string _port, int _curBaudRate, int _primaryBaudRate, int _gpioBaudRate=115200, int _auxBaudRate=115200)
This function can be used to set the buad rate independent of the other functions of the driver...
global variables used to store packet information.
static int CreateFilterOptionsPacket(filter_options_packet_t &, bool _permanent=true, uint8_t _vehicle_type=vehicle_type_car, bool _internal_gnss_enabled=true, bool _atmospheric_altitude_enabled=true, bool _velocity_heading_enabled=true, bool _reversing_detection_enabled=true, bool _motion_analysis_enabled=true)
static int CalculateRequiredBaud(KvhPacketRequest &)
KVH Packet storing class header.
static int FindCurrentBaudRate(std::string, int)
This function tries each possible setting of baudrates until it either finds one that is receiving pa...
std::vector< std::pair< packet_id_e, uint16_t > > KvhPacketRequest
static int CreatePacketPeriodsPacket(KvhPacketRequest &_packetsRequested, packet_periods_packet_t &_packetPeriods)


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