KumarRobotics / ublox

A driver for ublox gps
BSD 3-Clause "New" or "Revised" License
438 stars 381 forks source link

Device is cold restarting every launch. #59

Closed AlexKaravaev closed 2 years ago

AlexKaravaev commented 5 years ago

Hi everyone!

I have U-blox F9P receiver and this driver seems to be working properly, except sometimes receiving NACK messages, but that is alright, because lat/lon/alt values are precise.

But every time I launch ublox-node with given launch and config file below, the device is cold-resetting, which leads to 15 sec. restart.

What should I change in the code in order to disable this reseting? The configuration of the device stays the same between launches.


Launch file

<?xml version="1.0" encoding="UTF-8"?>

<launch>
  <arg name="node_name" />
  <arg name="param_file_name" doc="name of param file, e.g. rover" default="f9p" />
  <arg name="output" default="screen" />
  <arg name="respawn" default="true" />
  <arg name="respawn_delay" default="30" />
  <arg name="clear_params" default="true" />

  <node pkg="ublox_gps" type="ublox_gps" name="$(arg node_name)"
        output="$(arg output)" 
        clear_params="$(arg clear_params)"
        respawn="$(arg respawn)" 
        respawn_delay="$(arg respawn_delay)">
    <rosparam command="load" 
              file="$(find ublox_gps)/config/$(arg param_file_name).yaml" />
  </node>
</launch>

Config file

dynamic_model: portable
fix_mode: auto # Switches between 2D/3D automatically
dr_limit: 0 # Dead reckoning limit
enable_ppp: false # Advanced setting not supported by all devices

rate: 20 # Measurement rate in Hz
nav_rate: 4 # in number of measurement cycles
device: /dev/ttyACM0
frame_id: gps_ublox1

dynamic_model: automotive

uart1:
    baudrate: 38400 # baudrate is device specific, check the device manual
    in: 1 # UBX
    out: 2 # NMEA
gnss:
    gps: true # (not required since it defaults to true)
    glonass: true
    beidou: true
    qzss: true
    sbas: false
    galileo: true

inf:
    all: true # Whether to display INF messages
publish:
    all: true
    aid:
        hui: false
subscribe:
    all: true # Subscribe to all messages
    aid:
        all: false # ... except AID messages``

ROSOUT

[ INFO] [Time: 1564987772.645131008]: [/GPS/ubx_receiver] U-Blox: Opened serial port /dev/ttyACM0
[DEBUG] [Time: 1564987772.645646104]: [/GPS/ubx_receiver] Configuring UART1 baud rate: 38400, In/Out Protocol: 1 / 2
[DEBUG] [Time: 1564987772.646969144]: [/GPS/ubx_receiver] EXT CORE 1.00 (61ce84), HW VER: 00190000
[DEBUG] [Time: 1564987772.647008517]: [/GPS/ubx_receiver] ROM BASE 0xDD3FE36C
[DEBUG] [Time: 1564987772.647047500]: [/GPS/ubx_receiver] FWVER=HPG 1.00
[DEBUG] [Time: 1564987772.647064783]: [/GPS/ubx_receiver] PROTVER=27.00
[DEBUG] [Time: 1564987772.647080632]: [/GPS/ubx_receiver] MOD=ZED-F9P
[DEBUG] [Time: 1564987772.647098306]: [/GPS/ubx_receiver] GPS;GLO;GAL;BDS
[DEBUG] [Time: 1564987772.647113384]: [/GPS/ubx_receiver] QZSS
[ INFO] [Time: 1564987772.647152607]: [/GPS/ubx_receiver] U-Blox Firmware Version: 8
[ WARN] [Time: 1564987772.647209724]: [/GPS/ubx_receiver] Product category HPG  from MonVER message not recognized options are HPG REF, HPG ROV, TIM, ADR, UDR, FTS, SPG
[DEBUG] [Time: 1564987772.664570786]: [/GPS/ubx_receiver] Configuring measurement rate to 50 ms and nav rate to 4 cycles
[DEBUG] [Time: 1564987772.665207169]: [/GPS/ubx_receiver] Disabling PPP
[DEBUG] [Time: 1564987772.665670317]: [/GPS/ubx_receiver] Setting dynamic model to 4
[DEBUG] [Time: 1564987772.666083642]: [/GPS/ubx_receiver] Setting fix mode to 3
[DEBUG] [Time: 1564987772.666458775]: [/GPS/ubx_receiver] Setting DR Limit to 0
[DEBUG] [Time: 1564987772.667392075]: [/GPS/ubx_receiver] Read GNSS config.
[DEBUG] [Time: 1564987772.667415579]: [/GPS/ubx_receiver] Num. tracking channels in hardware: 60
[DEBUG] [Time: 1564987772.667434314]: [/GPS/ubx_receiver] Num. tracking channels to use: 60
[DEBUG] [Time: 1564987772.667456365]: [/GPS/ubx_receiver] QZSS Configuration is different 1, 1
[DEBUG] [Time: 1564987772.667474730]: [/GPS/ubx_receiver] QZSS Configuration: 286326785
[DEBUG] [Time: 1564987772.667492683]: [/GPS/ubx_receiver] QZSS Configuration: 286326785
[DEBUG] [Time: 1564987772.667514324]: [/GPS/ubx_receiver] Re-configuring GNSS.
[ WARN] [Time: 1564987772.668483641]: [/GPS/ubx_receiver] GNSS re-configured, cold resetting device.
[ WARN] [Time: 1564987772.668508167]: [/GPS/ubx_receiver] Resetting u-blox. If device address changes, node must be relaunched.
scott-robotics commented 4 years ago

Seems to be the on-board settings for QZSS differing from the node parameter default (L1C/A). This is due to the F9P having the L2 band enabled, which is not support on M8 modules. To rectify the issue you are seeing i set the QZSS parameters to match the F9P default. In the yaml:

 gnss:
    glonass: true
    beidou: true
    qzss: true
    galileo: true
    qzss_sig_cfg: 0x110000
mpena2099 commented 3 years ago

Thanks @scottnothing .