Skip to content

Commit d407bd0

Browse files
Ryanf55tfootepeci1
authored
[J-Turtle] Fix uninitialized values in NavSatFix and add missing NavSatStatus UNKNOWN (#220)
* Fix unitialized values in NavSatFix and add missing UNKNOWN * Fixes #196 * Fix default initialization instead of constants * Define SERVICE_UNKNOWN Signed-off-by: Ryan Friedman <[email protected]> Signed-off-by: Tully Foote <[email protected]> Co-authored-by: Tully Foote <[email protected]> Co-authored-by: Martin Pecka <[email protected]>
1 parent 91fef14 commit d407bd0

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

sensor_msgs/msg/NavSatStatus.msg

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,16 +4,18 @@
44
# type and the last time differential corrections were received. A
55
# fix is valid when status >= STATUS_FIX.
66

7+
int8 STATUS_UNKNOWN = -2 # status is not yet set
78
int8 STATUS_NO_FIX = -1 # unable to fix position
89
int8 STATUS_FIX = 0 # unaugmented fix
910
int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation
1011
int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation
1112

12-
int8 status
13+
int8 status -2 # STATUS_UNKNOWN
1314

1415
# Bits defining which Global Navigation Satellite System signals were
1516
# used by the receiver.
1617

18+
uint16 SERVICE_UNKNOWN = 0 # Remember service is a bitfield, so checking (service & SERVICE_UNKNOWN) will not work. Use == instead.
1719
uint16 SERVICE_GPS = 1
1820
uint16 SERVICE_GLONASS = 2
1921
uint16 SERVICE_COMPASS = 4 # includes BeiDou.

0 commit comments

Comments
 (0)