Static Public Member Functions | List of all members
kvh::KvhDeviceConfig Class Reference

#include <kvh_geo_fog_3d_device_configuration.hpp>

Static Public Member Functions

static int CalculateRequiredBaud (KvhPacketRequest &)
 
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 CreateOdometerOptionsPacket (odometer_configuration_packet_t &, bool _permanent=true, float _odom_pulse_to_meters=0.000583, bool _odom_auto_cal=true)
 
static int CreatePacketPeriodsPacket (KvhPacketRequest &_packetsRequested, packet_periods_packet_t &_packetPeriods)
 
static int FindCurrentBaudRate (std::string, int)
 This function tries each possible setting of baudrates until it either finds one that is receiving packets from the kvh, or runs out of possibilities. More...
 
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. In most cases baud will need to be set once at the beginning, and then left alone unless more packets are added. More...
 

Detailed Description

Definition at line 47 of file kvh_geo_fog_3d_device_configuration.hpp.

Member Function Documentation

◆ CalculateRequiredBaud()

int kvh::KvhDeviceConfig::CalculateRequiredBaud ( KvhPacketRequest _packetsRequested)
static
kvh::KvhPacketRequest packetRequest = {
// Create packet timer
}
Parameters
_packetsRequested[in] The list of selected packet id's and their associated frequencies

CALCULATING BAUDRATE Formula: Data throughput = (packet_length + 5 (for fixed packet overhead)) * rate Minimum baud = data throughput * 11

Attention
The maximum allowable hz is 1000, any input above that will return an error code
Returns
int The required baud rate for the packets requested. >= 0 = Success, calculated baud rate -1 = Unsupported packet entered -2 = Duplicate packat id's -3 = Packet frequency exceeds max hz

Definition at line 321 of file device_configuration.cpp.

◆ CreateFilterOptionsPacket()

int kvh::KvhDeviceConfig::CreateFilterOptionsPacket ( filter_options_packet_t _filterOptions,
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
if (kvh::KvhDeviceConfig::CreateFilterOptionsPacket(filterOptions, ... // Additional options) != 0)
// Error
// Use filter options
Parameters
[out]_filterOptionsThe created filter options packet
[in]_permanentWhether the options should persist through reset. Default true
[in]_vehicle_typeDetermines the type of the vehicle. Used in internal kalman filter. Default: vehicle_type_car, range 0-13
[in]_internal_gnss_enabledWhether gnss capabilities are enabled. Default true
[in]_atmospheric_altitude_enabledWhether atmospheric altitude capabilitites are enabled. Default true
[in]_velocity_heading_enabledWhether velocity heading is enabled. Default true
[in]_reversing_detection_enabledWhether detecting reverse motion is enabled. Default true
[in]_motion_analysis_enabledWhether motion analysis is enabled. Default true
Returns
int 0 = Success -1 = Vehicle type out of range

Definition at line 138 of file device_configuration.cpp.

◆ CreateOdometerOptionsPacket()

int kvh::KvhDeviceConfig::CreateOdometerOptionsPacket ( odometer_configuration_packet_t _odometerOptions,
bool  _permanent = true,
float  _odom_pulse_to_meters = 0.000583,
bool  _odom_auto_cal = true 
)
static
if (kvh::KvhDeviceConfig::CreateOdometerOptionsPacket(odometerOptions, ... // Additional options) != 0)
// Error
// Use filter options
Parameters
[out]_odometerOptionsThe created odometer options packet
[in]_permanentWhether the options should persist through reset. Default true
[in]_odom_pulse_to_metersThe number of meters traveled per pulse
[in]_odom_auto_calIf the KVH should automatically calibrate the odometer
Returns
int 0 = Success -2 = Vehicle type out of range

Definition at line 176 of file device_configuration.cpp.

◆ CreatePacketPeriodsPacket()

int kvh::KvhDeviceConfig::CreatePacketPeriodsPacket ( KvhPacketRequest _packetsRequested,
packet_periods_packet_t _packetPeriods 
)
static
kvh::KvhPacketRequest packRequest = {
// Fill in packets
}
if (kvh::KvhDeviceConfig::CreatePacketPeriodsPacket(packRequest, periodsPacket) != 0)
// Error
// Use packet periods packet
Parameters
[in]_packetsRequestedVector of the packets requested and their associated frequencies
[out]_packetPeriodsA correctly constructed packet periods packet
Returns
int 0 = Success >0 = Number of unsupported or duplicated packets <0 = Error: Too many packets requested

PACKET RATE -> PACKET PERIOD Formula for how packet frequency relates to packet period: Packet Rate = 1000000/(Packet Period * Packet Timer Period)Hz - From Manual

Packet Timer Period can also be set, but we will use its default of 1000us for now So, given packet rate, the packet period we need to input is

1000000/(Packet Rate * 1000) = Packet Period 1000/Packet Rate = Packet Period

Definition at line 75 of file device_configuration.cpp.

◆ FindCurrentBaudRate()

int kvh::KvhDeviceConfig::FindCurrentBaudRate ( std::string  _port,
int  _startingBaud 
)
static

This function tries each possible setting of baudrates until it either finds one that is receiving packets from the kvh, or runs out of possibilities.

std::string port{'/dev/ttyUSB1'};
int curBaud = FindCurrentBaudRate(port);
Parameters
[in]_portThe port on the computer the kvh is connected to (e.g. '/dev/ttyUSB0')
Returns
int The current baudrate of the kvh if found, -1 otherwise

Definition at line 250 of file device_configuration.cpp.

◆ SetBaudRate()

int kvh::KvhDeviceConfig::SetBaudRate ( std::string  _port,
int  _curBaudRate,
int  _primaryBaudRate,
int  _gpioBaudRate = 115200,
int  _auxBaudRate = 115200 
)
static

This function can be used to set the buad rate independent of the other functions of the driver. In most cases baud will need to be set once at the beginning, and then left alone unless more packets are added.

std::string port{'/dev/USB0'};
int curBaud = 115200;
int prevBaud = 9600;
kvh::KvhDeviceConfig::SetBaudRate(port, curBaud, prevBaud);
Parameters
[in]_portThe port connected to the kvh (Ex. /dev/ttyS0)
[in]_curBaudRateThe current baud rate, required to connect and change baud rate
[in]_primaryBaudRateThe rate to use for the primary RS-422 communications
[in]_gpioBaudRateThe rate to use for the GPIO pins
[in]_auxBaudRateThe rate to use for the Auxiliary RS-232 port
Todo:

Add way to set gpio and auxiliary baud rates to their current values

Figure out how this function may be tested better

Returns
int -1 = Failure to open port -2 = Failure to set baud rate

Definition at line 208 of file device_configuration.cpp.


The documentation for this class was generated from the following files:
kvh::KvhDeviceConfig::CreatePacketPeriodsPacket
static int CreatePacketPeriodsPacket(KvhPacketRequest &_packetsRequested, packet_periods_packet_t &_packetPeriods)
Definition: device_configuration.cpp:75
packet_periods_packet_t
Definition: spatial_packets.h:779
kvh::KvhPacketRequest
std::vector< std::pair< packet_id_e, uint16_t > > KvhPacketRequest
Definition: kvh_geo_fog_3d_packet_storage.hpp:65
filter_options_packet_t
Definition: spatial_packets.h:821
kvh::KvhDeviceConfig::CreateFilterOptionsPacket
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)
Definition: device_configuration.cpp:138
kvh::KvhDeviceConfig::CalculateRequiredBaud
static int CalculateRequiredBaud(KvhPacketRequest &)
Definition: device_configuration.cpp:321
kvh::KvhDeviceConfig::CreateOdometerOptionsPacket
static int CreateOdometerOptionsPacket(odometer_configuration_packet_t &, bool _permanent=true, float _odom_pulse_to_meters=0.000583, bool _odom_auto_cal=true)
Definition: device_configuration.cpp:176
kvh::KvhDeviceConfig::SetBaudRate
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....
Definition: device_configuration.cpp:208
kvh::KvhDeviceConfig::FindCurrentBaudRate
static int FindCurrentBaudRate(std::string, int)
This function tries each possible setting of baudrates until it either finds one that is receiving pa...
Definition: device_configuration.cpp:250
odometer_configuration_packet_t
Definition: spatial_packets.h:889


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