ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | List of all members
semantic_components::GPSSensor< sensor_option > Class Template Reference
Inheritance diagram for semantic_components::GPSSensor< sensor_option >:
Inheritance graph
[legend]
Collaboration diagram for semantic_components::GPSSensor< sensor_option >:
Collaboration graph
[legend]

Public Member Functions

 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)
 
- Public Member Functions inherited from semantic_components::SemanticComponentInterface< sensor_msgs::msg::NavSatFix >
 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.
 

Additional Inherited Members

- Protected Attributes inherited from semantic_components::SemanticComponentInterface< sensor_msgs::msg::NavSatFix >
std::string name_
 
std::vector< std::string > interface_names_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > state_interfaces_
 

Member Function Documentation

◆ get_altitude()

template<GPSSensorOption sensor_option>
double semantic_components::GPSSensor< sensor_option >::get_altitude ( ) const
inline

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>>
const std::array< double, 9 > & semantic_components::GPSSensor< sensor_option >::get_covariance ( )
inline

Return covariance reported by a GPS.

Returns
Covariance array.

◆ get_latitude()

template<GPSSensorOption sensor_option>
double semantic_components::GPSSensor< sensor_option >::get_latitude ( ) const
inline

Return latitude reported by a GPS

Returns
Latitude.

◆ get_longitude()

template<GPSSensorOption sensor_option>
double semantic_components::GPSSensor< sensor_option >::get_longitude ( ) const
inline

Return longitude reported by a GPS

Returns
Longitude.

◆ get_service()

template<GPSSensorOption sensor_option>
uint16_t semantic_components::GPSSensor< sensor_option >::get_service ( ) const
inline

Return service used by GPS e.g. fix/no_fix

Returns
Service

◆ get_status()

template<GPSSensorOption sensor_option>
int8_t semantic_components::GPSSensor< sensor_option >::get_status ( ) const
inline

Return GPS's status e.g. fix/no_fix

Returns
Status

◆ get_values_as_message()

template<GPSSensorOption sensor_option>
bool semantic_components::GPSSensor< sensor_option >::get_values_as_message ( sensor_msgs::msg::NavSatFix &  message)
inline

Fills a NavSatFix message from the current values.


The documentation for this class was generated from the following file: