Skip to content

adding launch files for sparkfun L1/L5 NEO-F10n sensor #262

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,12 @@ The `ublox` package provides support for [u-blox](http://www.u-blox.com) GPS rec

The driver was originally written by Johannes Meyer. Changes made later are detailed in the version history below.


launch with
```
roslaunch ublox_gps neo_f10n.launch
```

## Options

Example .yaml configuration files are included in `ublox_gps/config`. Consult the u-blox documentation for your device for the recommended settings.
Expand Down
67 changes: 67 additions & 0 deletions ublox_gps/config/neo-f10n.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
# Configuration for NEO-F10N L1/L5 GPS receiver

# Device configuration
device: /dev/ttyUSB0
frame_id: gps
baudrate: 38400
rate: 4 # Measurement rate in Hz
nav_rate: 1 # Navigation rate in measurement cycles
dynamic_model: automotive # Automotive, pedestrian, etc.
uart1:
baudrate: 38400
in: 7 # NMEA + UBX in
out: 1 # UBX out

# u-blox 9 protocol settings
ublox_version: 9
# Set to auto for best compatibility
fix_mode: auto

# Workaround: Rather than setting individual GNSS constellations
# which are triggering warnings, we're using a simpler approach
enable_galileo: false
enable_beidou: false
enable_glonass: false
gnss:
gps: false # Workaround for the "not supported" warning
glonass: false
beidou: false
galileo: false
navic: false
qzss: false
sbas: false

# Set this to true to use the survey-in feature for base stations
# This is usually not needed for a rover
use_adr: false
use_feature_assistance: false

# Fix for NMEA error - add required num_sv parameter
nmea:
set: true
version: 4.10
num_sv: 8 # Required parameter (number of space vehicles to report)
gga: true
gll: true
gsa: true
gsv: true
rmc: true
vtg: true
gst: true

# Enable UBX messages for position, velocity, etc.
publish:
nav:
pvt: true
sat: true
status: true
posecef: true
velecef: true

# INF messages
inf:
all: true

# Recommended to leave max_sbas at 0 unless needed
max_sbas: 0

51 changes: 51 additions & 0 deletions ublox_gps/config/neo_f10n.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
# Configuration for NEO-F10N L1/L5 GPS receiver

# Device configuration
device: /dev/ttyUSB0
frame_id: gps
baudrate: 38400
rate: 4 # Measurement rate in Hz
nav_rate: 1 # Navigation rate in measurement cycles
dynamic_model: automotive # Automotive, pedestrian, etc.
uart1:
baudrate: 38400
in: 7 # NMEA + UBX in
out: 1 # UBX out

# u-blox 9 protocol settings
protocol_version: 40 # Simplified from 40.00 for compatibility
ublox_version: 9
# Fix mode (2D, 3D, auto)
fix_mode: auto

# GNSS Options
gnss:
gps: true
glonass: false
beidou: true
galileo: true
navic: true
qzss: true
sbas: false

# Enable specific message types
# Enable NMEA messages
nmea:
set: true
version: 4.10
gga: true
gll: true
gsa: true
gsv: true
rmc: true
vtg: true
gst: true

# Enable UBX messages for position, velocity, etc.
publish:
nav:
pvt: true
sat: true
status: true
posecef: true
velecef: true
50 changes: 50 additions & 0 deletions ublox_gps/launch/neo_f10n.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="node_name" default="ublox_gps"/>
<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)"
respawn="$(arg respawn)"
respawn_delay="$(arg respawn_delay)"
clear_params="$(arg clear_params)">

<!-- Basic device parameters -->
<param name="device" value="/dev/ttyUSB0"/>
<param name="frame_id" value="gps"/>
<param name="baudrate" value="38400"/>
<param name="rate" value="4"/>
<param name="nav_rate" value="1"/>
<param name="dynamic_model" value="automotive"/>
<param name="ublox_version" value="9"/>
<param name="fix_mode" value="auto"/>
<param name="config_on_startup" value="false" />

<!-- UART Configuration -->
<param name="uart1/baudrate" value="38400"/>
<param name="uart1/in" value="7"/> <!-- NMEA + UBX in -->
<param name="uart1/out" value="1"/> <!-- UBX out -->

<!-- Important: Include the existing NMEA configuration -->
<rosparam command="load" file="$(find ublox_gps)/config/nmea.yaml" />

<!-- Message configuration -->
<param name="publish/nav/pvt" value="true"/>
<param name="publish/nav/sat" value="true"/>
<param name="publish/nav/status" value="true"/>
<param name="inf/all" value="true"/>

<!-- Avoid problematic GNSS settings -->
<param name="enable_galileo" value="false"/>
<param name="enable_beidou" value="false"/>
<param name="enable_glonass" value="false"/>
<param name="gnss/gps" value="false"/>
<param name="gnss/galileo" value="false"/>
<param name="gnss/beidou" value="false"/>
<param name="max_sbas" value="0"/>
</node>
</launch>