Public Member Functions | Private Member Functions | Private Attributes | List of all members
kvh::Driver Class Reference

Driver worker class for the KVH Geo Fog 3D. More...

#include <kvh_geo_fog_3d_driver.hpp>

Public Member Functions

int AddPacket (packet_id_e)
 
int Cleanup ()
 Cleanup and close our connections. More...
 
 Driver (bool _debug=false)
 Initializes connected status, port to use, and if debug printing is turned on. More...
 
template<class T >
int GetPacket (packet_id_e _packetId, T &_packet)
 Retrieves the requested packets that are currently stored. Use PacketIsUpdated and SetPacketUpdated to keep track of if the packets have been updated since last use. More...
 
int Init (const std::string &_port, KvhPacketRequest &_packetsRequested)
 
int Init (const std::string &_port, KvhPacketRequest &_packetsRequested, KvhInitOptions _initOptions)
 
int Once ()
 Do a single data read from the device. More...
 
bool PacketIsUpdated (packet_id_e)
 Use this function to determine if new packet data has arrived since the last time you checked. More...
 
int RequestPacket (packet_id_e)
 This function is used to request packets that you only want once or that cannot be requested through the packet periods packet. For example, we wish to access the pulse length from the odom configuration packet, which is only available by requesting in this method. More...
 
int SetPacketUpdated (packet_id_e, bool)
 Use this function to set that the packet has been updated (though the driver will usually do that itself), or use it to notify the driver that you have used the most recent packet. More...
 
 ~Driver ()
 Destructor. Will automatically cleanup the driver. More...
 

Private Member Functions

int DecodePacket (an_packet_t *)
 
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 to capture all of the data. The utm_fix struct type is extended from utm_packet to include the missing zone information. More...
 
int SendPacket (an_packet_t *)
 Wrapper function for more easily sending an packets via serial port. More...
 

Private Attributes

an_decoder_t anDecoder_
 Decoder for decoding incoming AN encoded packets. More...
 
bool connected_
 True if we're connected to the localization unit. More...
 
bool debug_ {false}
 Set true to print debug statements. More...
 
KvhInitOptions defaultOptions_
 If no init options are passed in, use this as the default. More...
 
KvhDeviceConfig deviceConfig_
 Class responsible for configuring kvh geo fog. More...
 
const uint32_t PACKET_PERIOD {50}
 equal packet frequency. See manual for equation on how Packet Period affects packet rate. More...
 
std::vector< packet_id_epacketRequests_
 
KvhPacketStorage packetStorage_
 Class responsible for handling packets and ensuring consistency. More...
 
std::string port_
 Port to connect to the kvh through. Ex. "/dev/ttyUSB0". More...
 

Detailed Description

Driver worker class for the KVH Geo Fog 3D.

Todo:

Add functions for changing output packets and packet rate

Make packet output rate variable

Definition at line 83 of file kvh_geo_fog_3d_driver.hpp.

Constructor & Destructor Documentation

◆ Driver()

kvh::Driver::Driver ( bool  _debug = false)
explicit

Initializes connected status, port to use, and if debug printing is turned on.

Parameters
_debug[in] Determines if debug statements are printed.

Definition at line 61 of file driver_main.cpp.

◆ ~Driver()

kvh::Driver::~Driver ( )

Destructor. Will automatically cleanup the driver.

Definition at line 71 of file driver_main.cpp.

Member Function Documentation

◆ AddPacket()

int kvh::Driver::AddPacket ( packet_id_e  _packetId)
kvhDriver.AddPacket(packet_id);
Parameters
_packetIdThe id of the packet to set the status of
Returns
0 = success, 1 = duplicate, -1 = Error, unsupported

Definition at line 358 of file driver_main.cpp.

◆ Cleanup()

int kvh::Driver::Cleanup ( )

Cleanup and close our connections.

kvh::Driver kvhDriver
// Initialize and use driver
kvhDriver.Cleanup();
Returns
[int]: 0 = success, > 0 = warning, < 0 = failure

Definition at line 394 of file driver_main.cpp.

◆ DecodePacket()

int kvh::Driver::DecodePacket ( an_packet_t _anPacket)
private
Parameters
_anPacket[in] The packet to decode into a Kvh packet type
Returns
[int]: 0 = success, -1 = Not in list of currently stored packets -2 = Unable to decode packet
Todo:

replace if(debug) statements with logging

Should decode packets be moved out of driver?

Definition at line 79 of file decode_packets.cpp.

◆ DecodeUtmFix()

int kvh::Driver::DecodeUtmFix ( utm_fix _utmPacket,
an_packet_t _anPacket 
)
private

The current api given by kvh incorrectly deals with this packet so we needed to write our own decoder to capture all of the data. The utm_fix struct type is extended from utm_packet to include the missing zone information.

Parameters
_utmPacket[out] Our corrected utm packet
_anPacket[in] The an packet to decode
Returns
[int]: 0 = Success -1 = Failure, packet was not of type utm, or not correct length

Definition at line 54 of file decode_packets.cpp.

◆ GetPacket()

template<class T >
kvh::Driver::GetPacket ( packet_id_e  _packetId,
T &  _packet 
)
inline

Retrieves the requested packets that are currently stored. Use PacketIsUpdated and SetPacketUpdated to keep track of if the packets have been updated since last use.

Parameters
[in]_packetIdThe id of the packet you wish to retrieve
[out]_packetThe retrieved packet data
Returns
0 if successful, <0 if error
Packet packet;
kvhDriver.GetPacket(packet_id, packet);

Definition at line 190 of file kvh_geo_fog_3d_driver.hpp.

◆ Init() [1/2]

int kvh::Driver::Init ( const std::string &  _port,
KvhPacketRequest _packetsRequested 
)
std::vector<packet_id_e> packetRequest{packet_id_system_state, packet_id_satellites};
std::string kvhPort("/dev/ttyUSB0");
kvh::Driver kvhDriver;
kvhDriver.Init(kvhPort, packetRequest);

Definition at line 115 of file driver_main.cpp.

◆ Init() [2/2]

int kvh::Driver::Init ( const std::string &  _port,
KvhPacketRequest _packetsRequested,
KvhInitOptions  _initOptions 
)
std::vector<packet_id_e> packetRequest{packet_id_system_state, packet_id_satellites};
std::string kvhPort("/dev/ttyUSB0");
kvh::KvhInitOptions initOptions;
initOptions.baud = 230600;
... // Aditional options
kvh::Driver kvhDriver;
kvhDriver.Init(kvhPort, packetRequest, initOptions); *

Definition at line 138 of file driver_main.cpp.

◆ Once()

int kvh::Driver::Once ( )

Do a single data read from the device.

std::vector<packet_id_e> packetRequest{packet_id_system_state, packet_id_satellites};
KvhPacketMap packetMap;
kvh::Driver kvhDriver;
kvhDriver.CreatePacketMap(packetMap, packetRequest); // Populate map
kvhDriver.Once(kvhDriver); // Collect data
// Check if a packet was retrieved
if (packetMap[packet_id_system_state].first)
{
system_state_packet_t sysPacket = *static_cast<system_state_packet_t *>(packetMap[packet_id_system_state].second.get());
.... // Do stuff with the retrived packet
}
Returns
[int]: 0 = success -1 = CRC16 failure -2 = LRC failure

Single data packet read.

Attention
This function is a bit of a mess, due to how their api has a different function for every single type of packet. Our goal is to be able to deal with all of them simply within one single function, but that brings a lot of typing problems into the mix. Namely making sure that we have the correct type of struct, and then calling the correct decoding function for that struct.

Definition at line 276 of file driver_main.cpp.

◆ PacketIsUpdated()

bool kvh::Driver::PacketIsUpdated ( packet_id_e  _packetId)

Use this function to determine if new packet data has arrived since the last time you checked.

if(kvhDriver.PacketIsUpdated(packet_id))
{
// Do stuff, e.g.
Packet packet;
kvhDriver.GetPacket(packet_id, packet)
}
Parameters
_packetIdThe id of the packet you are checking
Returns
True if the packet has been updated, false if not

Definition at line 334 of file driver_main.cpp.

◆ RequestPacket()

int kvh::Driver::RequestPacket ( packet_id_e  _requestedPacket)

This function is used to request packets that you only want once or that cannot be requested through the packet periods packet. For example, we wish to access the pulse length from the odom configuration packet, which is only available by requesting in this method.

kvhDriver.requestPacket(packet_id);
// Packet will be picked up next time Once() is called
Parameters
_requestedPacketThe id of the packet you want to request
Returns
0 if successful, <0 if error
Todo:
Verify with KVH that odom configuration is not available through packet periods. I tried it and got errors with both testing programatically and using their GUI.

Definition at line 376 of file driver_main.cpp.

◆ SendPacket()

int kvh::Driver::SendPacket ( an_packet_t _anPacket)
private

Wrapper function for more easily sending an packets via serial port.

Parameters
_anPacket[in] The an packet to transmit

Definition at line 86 of file driver_main.cpp.

◆ SetPacketUpdated()

int kvh::Driver::SetPacketUpdated ( packet_id_e  _packetId,
bool  _updateStatus 
)

Use this function to set that the packet has been updated (though the driver will usually do that itself), or use it to notify the driver that you have used the most recent packet.

kvhDriver.SetPacketUpdated(packet_id, true/false);
Parameters
_packetIdThe id of the packet you want to set the status of
_updateStatusThe value you want to set the packet to.

Definition at line 348 of file driver_main.cpp.

Member Data Documentation

◆ anDecoder_

an_decoder_t kvh::Driver::anDecoder_
private

Decoder for decoding incoming AN encoded packets.

Definition at line 90 of file kvh_geo_fog_3d_driver.hpp.

◆ connected_

bool kvh::Driver::connected_
private

True if we're connected to the localization unit.

Definition at line 86 of file kvh_geo_fog_3d_driver.hpp.

◆ debug_

bool kvh::Driver::debug_ {false}
private

Set true to print debug statements.

Definition at line 91 of file kvh_geo_fog_3d_driver.hpp.

◆ defaultOptions_

KvhInitOptions kvh::Driver::defaultOptions_
private

If no init options are passed in, use this as the default.

Definition at line 95 of file kvh_geo_fog_3d_driver.hpp.

◆ deviceConfig_

KvhDeviceConfig kvh::Driver::deviceConfig_
private

Class responsible for configuring kvh geo fog.

Definition at line 97 of file kvh_geo_fog_3d_driver.hpp.

◆ PACKET_PERIOD

const uint32_t kvh::Driver::PACKET_PERIOD {50}
private

equal packet frequency. See manual for equation on how Packet Period affects packet rate.

Setting for determining packet rate. Note: Does not

Definition at line 88 of file kvh_geo_fog_3d_driver.hpp.

◆ packetRequests_

std::vector<packet_id_e> kvh::Driver::packetRequests_
private

Keeps a list of packet requests we have sent that we should recieve achknowledgement packets for. Add to list in SendPacket, remove in Once (this may cause a time delay problem where the packet is already gone by the time this function is called)

Definition at line 92 of file kvh_geo_fog_3d_driver.hpp.

◆ packetStorage_

KvhPacketStorage kvh::Driver::packetStorage_
private

Class responsible for handling packets and ensuring consistency.

Definition at line 96 of file kvh_geo_fog_3d_driver.hpp.

◆ port_

std::string kvh::Driver::port_
private

Port to connect to the kvh through. Ex. "/dev/ttyUSB0".

Definition at line 87 of file kvh_geo_fog_3d_driver.hpp.


The documentation for this class was generated from the following files:
kvh::KvhInitOptions
Definition: kvh_geo_fog_3d_driver.hpp:58
kvh::KvhPacketMap
std::map< packet_id_e, std::pair< bool, std::shared_ptr< void > > > KvhPacketMap
Definition: kvh_geo_fog_3d_packet_storage.hpp:58
kvh::Driver
Driver worker class for the KVH Geo Fog 3D.
Definition: kvh_geo_fog_3d_driver.hpp:83
packet_id_satellites
@ packet_id_satellites
Definition: spatial_packets.h:70
packet_id_system_state
@ packet_id_system_state
Definition: spatial_packets.h:60
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::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::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::Driver::Init
int Init(const std::string &_port, KvhPacketRequest &_packetsRequested)
Definition: driver_main.cpp:115
system_state_packet_t
Definition: spatial_packets.h:246


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