45 POSE_BROADCASTER_PUBLIC controller_interface::CallbackReturn
on_init()
override;
47 POSE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_configure(
48 const rclcpp_lifecycle::State & previous_state)
override;
50 POSE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_activate(
51 const rclcpp_lifecycle::State & previous_state)
override;
53 POSE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_deactivate(
54 const rclcpp_lifecycle::State & previous_state)
override;
56 POSE_BROADCASTER_PUBLIC controller_interface::return_type
update(
57 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
60 std::shared_ptr<ParamListener> param_listener_;
63 std::unique_ptr<semantic_components::PoseSensor> pose_sensor_;
65 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pose_publisher_;
66 std::unique_ptr<realtime_tools::RealtimePublisher<geometry_msgs::msg::PoseStamped>>
69 std::optional<rclcpp::Duration> tf_publish_period_;
70 rclcpp::Time tf_last_publish_time_{0, 0, RCL_CLOCK_UNINITIALIZED};
71 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr tf_publisher_;
72 std::unique_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
73 realtime_tf_publisher_;
POSE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition pose_broadcaster.cpp:50
POSE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition pose_broadcaster.cpp:59
POSE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition pose_broadcaster.cpp:42