|
| GPSSensor (const std::string &name) |
|
int8_t | get_status () const |
|
uint16_t | get_service () const |
|
double | get_latitude () const |
|
double | get_longitude () const |
|
double | get_altitude () const |
|
template<typename U = void, typename = std::enable_if_t<sensor_option == GPSSensorOption::WithCovariance, U>> |
const std::array< double, 9 > & | get_covariance () |
|
bool | get_values_as_message (sensor_msgs::msg::NavSatFix &message) |
|
| SemanticComponentInterface (const std::string &name, const std::vector< std::string > &interface_names) |
|
| SemanticComponentInterface (const std::string &name, std::size_t size=0) |
|
bool | assign_loaned_state_interfaces (std::vector< hardware_interface::LoanedStateInterface > &state_interfaces) |
| Assign loaned state interfaces from the hardware.
|
|
void | release_interfaces () |
| Release loaned interfaces from the hardware.
|
|
virtual std::vector< std::string > | get_state_interface_names () |
| Definition of state interface names for the component.
|
|
bool | get_values (std::vector< double > &values) const |
| Return all values.
|
|
bool | get_values_as_message (sensor_msgs::msg::NavSatFix &) |
| Return values as MessageReturnType.
|
|
◆ 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