46 virtual void initialize_implementation_parameter_listener() = 0;
48 controller_interface::CallbackReturn
on_init()
override;
54 virtual controller_interface::CallbackReturn configure_odometry() = 0;
56 virtual bool update_odometry(
const rclcpp::Duration & period) = 0;
59 const std::shared_ptr<rmw_request_id_t> request_header,
60 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
61 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
65 controller_interface::CallbackReturn on_configure(
66 const rclcpp_lifecycle::State & previous_state)
override;
68 controller_interface::CallbackReturn on_activate(
69 const rclcpp_lifecycle::State & previous_state)
override;
71 controller_interface::CallbackReturn on_deactivate(
72 const rclcpp_lifecycle::State & previous_state)
override;
74 controller_interface::CallbackReturn on_cleanup(
75 const rclcpp_lifecycle::State & previous_state)
override;
77 controller_interface::CallbackReturn on_error(
78 const rclcpp_lifecycle::State & previous_state)
override;
81 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
84 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
86 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
87 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
88 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
89 using SteeringControllerStateMsg = control_msgs::msg::SteeringControllerStatus;
92 controller_interface::CallbackReturn set_interface_numbers(
93 size_t nr_state_itfs,
size_t nr_cmd_itfs,
size_t nr_ref_itfs);
95 std::shared_ptr<steering_controllers_library::ParamListener> param_listener_;
96 steering_controllers_library::Params params_;
101 ControllerTwistReferenceMsg current_ref_;
102 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
105 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ =
nullptr;
109 rclcpp::Publisher<ControllerStateMsgOdom>::SharedPtr odom_s_publisher_;
110 rclcpp::Publisher<ControllerStateMsgTf>::SharedPtr tf_odom_s_publisher_;
112 std::unique_ptr<ControllerStatePublisherOdom> rt_odom_state_publisher_;
113 ControllerStateMsgOdom odom_state_msg_;
114 std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_;
115 ControllerStateMsgTf tf_odom_state_msg_;
124 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
125 std::atomic<bool> set_odom_requested_{
false};
127 requested_odom_params_;
129 SteeringControllerStateMsg published_state_;
132 rclcpp::Publisher<SteeringControllerStateMsg>::SharedPtr controller_s_publisher_;
133 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
134 SteeringControllerStateMsg controller_state_msg_;
137 size_t nr_state_itfs_;
144 double last_linear_velocity_ = 0.0;
145 double last_angular_velocity_ = 0.0;
147 std::vector<std::string> traction_joints_state_names_;
148 std::vector<std::string> steering_joints_state_names_;
152 void reference_callback(
const std::shared_ptr<ControllerTwistReferenceMsg> msg);