Class GPSSensorBroadcaster

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

class GPSSensorBroadcaster : public controller_interface::ControllerInterface

Public Functions

virtual controller_interface::InterfaceConfiguration command_interface_configuration() const override
virtual controller_interface::InterfaceConfiguration state_interface_configuration() const override
virtual callback_return_type on_init() override
callback_return_type on_configure(const rclcpp_lifecycle::State &previous_state) override
callback_return_type on_activate(const rclcpp_lifecycle::State &previous_state) override
callback_return_type on_deactivate(const rclcpp_lifecycle::State &previous_state) override
virtual controller_interface::return_type update(const rclcpp::Time&, const rclcpp::Duration&) override

Protected Types

using GPSSensorOption = semantic_components::GPSSensorOption
using GPSSensorVariant = std::variant<std::monostate, semantic_components::GPSSensor<GPSSensorOption::WithCovariance>, semantic_components::GPSSensor<GPSSensorOption::WithoutCovariance>>
using StatePublisher = realtime_tools::RealtimePublisher<sensor_msgs::msg::NavSatFix>

Protected Functions

void setup_covariance()
callback_return_type setup_publisher()

Protected Attributes

GPSSensorVariant gps_sensor_
rclcpp::Publisher<sensor_msgs::msg::NavSatFix>::SharedPtr sensor_state_publisher_
std::unique_ptr<StatePublisher> realtime_publisher_
std::shared_ptr<gps_sensor_broadcaster::ParamListener> param_listener_ = {}
gps_sensor_broadcaster::Params params_
std::vector<std::string> state_names_