◆ get_altitude()
template<GPSSensorOption sensor_option>
Return altitude reported by a GPS
- Returns
- Altitude.
◆ get_covariance()
template<GPSSensorOption sensor_option>
template<typename U = void, typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>>
Return covariance reported by a GPS.
- Returns
- Covariance array.
◆ get_latitude()
template<GPSSensorOption sensor_option>
Return latitude reported by a GPS
- Returns
- Latitude.
◆ get_longitude()
template<GPSSensorOption sensor_option>
Return longitude reported by a GPS
- Returns
- Longitude.
◆ get_service()
template<GPSSensorOption sensor_option>
Return service used by GPS e.g. fix/no_fix
- Returns
- Service
◆ get_status()
template<GPSSensorOption sensor_option>
Return GPS's status e.g. fix/no_fix
- Returns
- Status
◆ get_values_as_message()
template<GPSSensorOption sensor_option>
Fills a NavSatFix message from the current values.
The documentation for this class was generated from the following file:
- ros2_control/controller_interface/include/semantic_components/gps_sensor.hpp