pub struct NavSatFix {
pub header: Header,
pub status: NavSatStatus,
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub position_covariance: Vec<f64>,
pub position_covariance_type: u8,
}Fields§
§header: Header§status: NavSatStatus§latitude: f64§longitude: f64§altitude: f64§position_covariance: Vec<f64>§position_covariance_type: u8Implementations§
pub const COVARIANCE_TYPE_UNKNOWN: u8 = 0u8
pub const COVARIANCE_TYPE_APPROXIMATED: u8 = 1u8
pub const COVARIANCE_TYPE_DIAGONAL_KNOWN: u8 = 2u8
pub const COVARIANCE_TYPE_KNOWN: u8 = 3u8
Trait Implementations§
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Deserialize this value from the given Serde deserializer. Read more
Source§const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatFix"
const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatFix"
Expected to be the combination pkg_name/type_name string describing the type to ros
Example: std_msgs/Header
Source§const MD5SUM: &'static str = "faa1756146a6a934d7e4ef0e3855c531"
const MD5SUM: &'static str = "faa1756146a6a934d7e4ef0e3855c531"
The computed md5sum of the message file and its dependencies
This field is optional, and only needed when using ros1 native communication
Source§const DEFINITION: &'static str = "# Navigation Satellite fix for any Global Navigation Satellite System\n#\n# Specified using the WGS 84 reference ellipsoid\n\n# header.stamp specifies the ROS time for this measurement (the\n# corresponding satellite time may be reported using the\n# sensor_msgs/TimeReference message).\n#\n# header.frame_id is the frame of reference reported by the satellite\n# receiver, usually the location of the antenna. This is a\n# Euclidean frame relative to the vehicle, not a reference\n# ellipsoid.\nstd_msgs/Header header\n\n# Satellite fix status information.\nNavSatStatus status\n\n# Latitude [degrees]. Positive is north of equator; negative is south.\nfloat64 latitude\n\n# Longitude [degrees]. Positive is east of prime meridian; negative is west.\nfloat64 longitude\n\n# Altitude [m]. Positive is above the WGS 84 ellipsoid\n# (quiet NaN if no altitude is available).\nfloat64 altitude\n\n# Position covariance [m^2] defined relative to a tangential plane\n# through the reported position. The components are East, North, and\n# Up (ENU), in row-major order.\n#\n# Beware: this coordinate system exhibits singularities at the poles.\nfloat64[9] position_covariance\n\n# If the covariance of the fix is known, fill it in completely. If the\n# GPS receiver provides the variance of each measurement, put them\n# along the diagonal. If only Dilution of Precision is available,\n# estimate an approximate covariance from that.\n\nuint8 COVARIANCE_TYPE_UNKNOWN = 0\nuint8 COVARIANCE_TYPE_APPROXIMATED = 1\nuint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\nuint8 COVARIANCE_TYPE_KNOWN = 3\n\nuint8 position_covariance_type"
const DEFINITION: &'static str = "# Navigation Satellite fix for any Global Navigation Satellite System\n#\n# Specified using the WGS 84 reference ellipsoid\n\n# header.stamp specifies the ROS time for this measurement (the\n# corresponding satellite time may be reported using the\n# sensor_msgs/TimeReference message).\n#\n# header.frame_id is the frame of reference reported by the satellite\n# receiver, usually the location of the antenna. This is a\n# Euclidean frame relative to the vehicle, not a reference\n# ellipsoid.\nstd_msgs/Header header\n\n# Satellite fix status information.\nNavSatStatus status\n\n# Latitude [degrees]. Positive is north of equator; negative is south.\nfloat64 latitude\n\n# Longitude [degrees]. Positive is east of prime meridian; negative is west.\nfloat64 longitude\n\n# Altitude [m]. Positive is above the WGS 84 ellipsoid\n# (quiet NaN if no altitude is available).\nfloat64 altitude\n\n# Position covariance [m^2] defined relative to a tangential plane\n# through the reported position. The components are East, North, and\n# Up (ENU), in row-major order.\n#\n# Beware: this coordinate system exhibits singularities at the poles.\nfloat64[9] position_covariance\n\n# If the covariance of the fix is known, fill it in completely. If the\n# GPS receiver provides the variance of each measurement, put them\n# along the diagonal. If only Dilution of Precision is available,\n# estimate an approximate covariance from that.\n\nuint8 COVARIANCE_TYPE_UNKNOWN = 0\nuint8 COVARIANCE_TYPE_APPROXIMATED = 1\nuint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\nuint8 COVARIANCE_TYPE_KNOWN = 3\n\nuint8 position_covariance_type"
The definition from the msg, srv, or action file
This field is optional, and only needed when using ros1 native communication
Auto Trait Implementations§
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more