50 GPIO_COMMAND_CONTROLLER_PUBLIC
53 GPIO_COMMAND_CONTROLLER_PUBLIC
56 GPIO_COMMAND_CONTROLLER_PUBLIC
59 GPIO_COMMAND_CONTROLLER_PUBLIC
60 CallbackReturn
on_init()
override;
62 GPIO_COMMAND_CONTROLLER_PUBLIC
63 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
65 GPIO_COMMAND_CONTROLLER_PUBLIC
66 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
68 GPIO_COMMAND_CONTROLLER_PUBLIC
69 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
71 GPIO_COMMAND_CONTROLLER_PUBLIC
72 controller_interface::return_type
update(
73 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
76 void store_command_interface_types();
77 void store_state_interface_types();
78 void initialize_gpio_state_msg();
79 void update_gpios_states();
80 controller_interface::return_type update_gpios_commands();
82 std::unordered_map<std::string, std::reference_wrapper<T>> create_map_of_references_to_interfaces(
83 const InterfacesNames & interfaces_from_params, std::vector<T> & configured_interfaces);
85 bool check_if_configured_interfaces_matches_received(
86 const InterfacesNames & interfaces_from_params,
const T & configured_interfaces);
87 void apply_state_value(
88 StateType & state_msg, std::size_t gpio_index, std::size_t interface_index)
const;
90 const CmdType & gpio_commands, std::size_t gpio_index,
91 std::size_t command_interface_index)
const;
92 InterfacesNames get_gpios_state_interfaces_names(
const std::string & gpio_name)
const;
93 bool update_dynamic_map_parameters();
94 std::vector<hardware_interface::ComponentInfo> get_gpios_from_urdf()
const;
97 InterfacesNames command_interface_types_;
98 InterfacesNames state_interface_types_;
99 MapOfReferencesToCommandInterfaces command_interfaces_map_;
100 MapOfReferencesToStateInterfaces state_interfaces_map_;
103 rclcpp::Subscription<CmdType>::SharedPtr gpios_command_subscriber_{};
105 std::shared_ptr<rclcpp::Publisher<StateType>> gpio_state_publisher_{};
106 std::shared_ptr<realtime_tools::RealtimePublisher<StateType>> realtime_gpio_state_publisher_{};
108 std::shared_ptr<gpio_command_controller_parameters::ParamListener> param_listener_{};
109 gpio_command_controller_parameters::Params params_;
GPIO_COMMAND_CONTROLLER_PUBLIC CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition gpio_command_controller.cpp:42