Program Listing for File settings.hpp

Return to documentation for file (/tmp/ws/src/septentrio_gnss_driver/include/septentrio_gnss_driver/communication/settings.hpp)

// *****************************************************************************
//
// © Copyright 2020, Septentrio NV/SA.
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//    1. Redistributions of source code must retain the above copyright
//       notice, this list of conditions and the following disclaimer.
//    2. Redistributions in binary form must reproduce the above copyright
//       notice, this list of conditions and the following disclaimer in the
//       documentation and/or other materials provided with the distribution.
//    3. Neither the name of the copyright holder nor the names of its
//       contributors may be used to endorse or promote products derived
//       from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// *****************************************************************************

#pragma once

#include <stdint.h>
#include <string>
#include <vector>

struct Osnma
{
    std::string mode;
    std::string ntp_server;
    bool keep_open;
};

struct RtkNtrip
{
    std::string id;
    std::string caster;
    uint32_t caster_port;
    std::string username;
    std::string password;
    std::string mountpoint;
    std::string version;
    bool tls;
    std::string fingerprint;
    std::string rtk_standard;
    std::string send_gga;
    bool keep_open;
};

struct RtkIpServer
{
    std::string id;
    uint32_t port;
    std::string rtk_standard;
    std::string send_gga;
    bool keep_open;
};

struct RtkSerial
{
    std::string port;
    uint32_t baud_rate;
    std::string rtk_standard;
    std::string send_gga;
    bool keep_open;
};

struct Rtk
{
    std::vector<RtkNtrip> ntrip;
    std::vector<RtkIpServer> ip_server;
    std::vector<RtkSerial> serial;
};

namespace device_type {
    enum DeviceType
    {
        TCP,
        SERIAL,
        SBF_FILE,
        PCAP_FILE
    };
} // namespace device_type

struct Settings
{
    bool activate_debug_log;
    std::string device;
    device_type::DeviceType device_type;
    std::string device_tcp_ip;
    std::string device_tcp_port;
    uint32_t udp_port;
    std::string udp_unicast_ip;
    std::string udp_ip_server;
    uint32_t tcp_port;
    std::string tcp_ip_server;
    std::string file_name;
    std::string login_user;
    std::string login_password;
    float reconnect_delay_s;
    uint32_t baudrate;
    std::string hw_flow_control;
    // Wether to configure Rx
    bool configure_rx;
    std::string datum;
    uint32_t polling_period_pvt;
    uint32_t polling_period_rest;
    float delta_e;
    float delta_n;
    float delta_u;
    std::string ant_type;
    std::string ant_aux1_type;
    std::string ant_serial_nr;
    std::string ant_aux1_serial_nr;
    bool use_ros_axis_orientation;
    double theta_x;
    double theta_y;
    double theta_z;
    double ant_lever_x;
    double ant_lever_y;
    double ant_lever_z;
    double poi_x;
    double poi_y;
    double poi_z;
    double vsm_x;
    double vsm_y;
    double vsm_z;
    double heading_offset;
    double pitch_offset;
    bool multi_antenna;
    bool ins_use_poi;
    std::string ins_initial_heading;
    float att_std_dev;
    float pos_std_dev;
    Rtk rtk;
    Osnma osnma;
    bool publish_gpgga;
    bool publish_gprmc;
    bool publish_gpgsa;
    bool publish_gpgsv;
    bool publish_measepoch;
    bool publish_aimplusstatus;
    bool publish_galauthstatus;
    bool publish_pvtcartesian;
    bool publish_pvtgeodetic;
    bool publish_basevectorcart;
    bool publish_basevectorgeod;
    bool publish_poscovcartesian;
    bool publish_poscovgeodetic;
    bool publish_velcovcartesian;
    bool publish_velcovgeodetic;
    bool publish_atteuler;
    bool publish_attcoveuler;
    bool publish_insnavcart;
    bool publish_insnavgeod;
    bool publish_imusetup;
    bool publish_velsensorsetup;
    bool publish_exteventinsnavgeod;
    bool publish_exteventinsnavcart;
    bool publish_extsensormeas;
    bool publish_gpst;
    bool publish_navsatfix;
    bool publish_gpsfix;
    bool publish_pose;
    bool publish_diagnostics;
    bool publish_imu;
    bool publish_localization;
    bool publish_localization_ecef;
    bool publish_twist;
    bool publish_tf;
    bool publish_tf_ecef;
    bool insert_local_frame = false;
    std::string local_frame_id;
    std::string septentrio_receiver_type;
    bool use_gnss_time;
    bool latency_compensation;
    std::string frame_id;
    std::string imu_frame_id;
    std::string poi_frame_id;
    std::string vsm_frame_id;
    std::string aux1_frame_id;
    std::string vehicle_frame_id;
    bool lock_utm_zone;
    int32_t leap_seconds = -128;
    bool read_from_sbf_log = false;
    bool read_from_pcap = false;
    std::string ins_vsm_ros_source;
    std::vector<bool> ins_vsm_ros_config = {false, false, false};
    bool ins_vsm_ros_variances_by_parameter = false;
    std::vector<double> ins_vsm_ros_variances = {-1.0, -1.0, -1.0};
    std::string ins_vsm_ip_server_id;
    uint32_t ins_vsm_ip_server_port;
    bool ins_vsm_ip_server_keep_open;
    std::string ins_vsm_serial_port;
    uint32_t ins_vsm_serial_baud_rate;
    bool ins_vsm_serial_keep_open;
};

struct Capabilities
{
    bool is_ins = false;
    bool has_heading = false;
    bool has_improved_vsm_handling = false;
};