-
Notifications
You must be signed in to change notification settings - Fork 1
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
add first version of gnns #1
Open
PonomarevDA
wants to merge
6
commits into
DS-015:main
Choose a base branch
from
PonomarevDA:pr-add-gnss
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from all commits
Commits
Show all changes
6 commits
Select commit
Hold shift + click to select a range
e1bd442
add first version of gnns for ds015
PonomarevDA 2778039
add spoofind and jamming indiction for gnns status
PonomarevDA 791ce0b
remove accidentally added TAI64.0.1 and add namespace kinematics
PonomarevDA 68de845
add RelativePosition.0.1
PonomarevDA cf9cf9d
add Covariance.0.1
PonomarevDA 176c8d8
fix few code style mistakes
PonomarevDA File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
# Geodetic position: latitude, longitude, and altitude. | ||
# The order is chosen to match the axis ordering of the NED frame. | ||
|
||
float64 latitude # [radian] | ||
float64 longitude # [radian] | ||
|
||
uavcan.si.unit.length.Scalar.1.0 altitude | ||
# Distance between the local mean sea level (MSL) and the focal point of the antenna. Positive altitude above the MSL. | ||
|
||
@sealed |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,14 @@ | ||
# This message outputs the covariance matrices for the position and velocity | ||
# solutions in the topocentric coordinate system defined as the local-level | ||
# North (N), East (E), Down (D) frame. As the covariance matrices are | ||
# symmetric, only the upper triangular part is output. | ||
|
||
float16[6] point_covariance_urt # [meter^2] | ||
# Upper-right triangle of the covariance matrix. | ||
# The position covariance is defined relative to a tangential plane through the specified latitude/longitude. | ||
# Element ordering: latitude, longitude, altitude. It is chosen to match the axis ordering of the NED frame. | ||
|
||
float16[6] velocity_covariance_urt # [meter^2] | ||
# [(meter/second)^2] Upper-right triangle of the covariance matrix. | ||
|
||
@sealed |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,33 @@ | ||
# A generic GNSS information. | ||
|
||
Status.0.1 status | ||
|
||
uint32 time_week_ms | ||
uint16 time_week | ||
# Time of week (TOW) timestamp indicates the GPS time at which the navigation epoch occurred. | ||
|
||
ds015.physics.kinematics.geodetic.Point.0.1 point | ||
uavcan.si.unit.velocity.Vector3.1.0 velocity | ||
uavcan.si.unit.angle.Scalar.1.0 yaw | ||
|
||
float16 horizontal_accuracy | ||
# Horizontal RMS accuracy estimate in m | ||
|
||
float16 vertical_accuracy | ||
# Vertical RMS accuracy estimate in m | ||
|
||
float16 speed_accuracy | ||
# 3D velocity RMS accuracy estimate in m/s | ||
|
||
uavcan.si.unit.angle.Scalar.1.0 yaw_accuracy | ||
# heading accuracy of the GPS in radians | ||
|
||
float16 hdop | ||
# Horizontal dilution of precision in meters | ||
|
||
float16 vdop | ||
# Vertical dilution of precision in meters | ||
|
||
uint8 num_sats | ||
|
||
@sealed |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
# Relative positioning information in NED frame | ||
# This message contains the relative position vector from the reference station to the rover. | ||
|
||
uint32 time_week_ms | ||
uint16 time_week | ||
# Time of week (TOW) timestamp indicates the GPS time at which the navigation epoch occurred. | ||
|
||
uavcan.si.unit.length.Vector3.1.0 relative_position | ||
# Alternatively, we can create physics.kinematics.cartesian.Point.0.1 with float32 | ||
|
||
@sealed |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,35 @@ | ||
# A generic GNSS information. | ||
|
||
truncated uint2 status | ||
uint2 STATUS_NO_FIX = 0 | ||
uint2 STATUS_TIME_ONLY = 1 | ||
uint2 STATUS_2D_FIX = 2 | ||
uint2 STATUS_3D_FIX = 3 | ||
|
||
truncated uint2 mode | ||
uint2 MODE_SINGLE = 0 | ||
uint2 MODE_DGPS = 1 | ||
uint2 MODE_RTK = 2 | ||
uint2 MODE_PPP = 3 | ||
|
||
truncated uint2 sub_mode | ||
uint2 SUB_MODE_DGPS_OTHER = 0 | ||
uint2 SUB_MODE_DGPS_SBAS = 1 | ||
uint2 SUB_MODE_RTK_FLOAT = 0 | ||
uint2 SUB_MODE_RTK_FIXED = 1 | ||
|
||
truncated uint2 jamming_state | ||
uint2 JAMMING_STATE_UNKNOWN = 0 | ||
uint2 JAMMING_STATE_OK = 1 | ||
uint2 JAMMING_STATE_WARNING = 2 | ||
uint2 JAMMING_STATE_CRITICAL = 3 | ||
# Indicates whether jamming has been detected or suspected by the receivers | ||
|
||
truncated uint2 spoofing_state | ||
uint2 SPOOFING_STATE_UNKNOWN = 0 | ||
uint2 SPOOFING_STATE_NONE = 1 | ||
uint2 SPOOFING_STATE_INDICATED = 2 | ||
uint2 SPOOFING_STATE_MULTIPLE = 3 | ||
# Indicates whether spoofing has been detected or suspected by the receivers | ||
|
||
@sealed |
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
heading accuracy?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
A different approach could be to separately send a relative position when it's available instead of just the dumbed down heading with no metadata.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Heading accuracy is just a little lower, it is called
yaw_accuracy
.I've added RelativePosition.0.1 dsdl. We can send it if it is available as a separate message. Is it what you mean?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Yes sending it separately (when available) makes sense.