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;
58 controller_interface::CallbackReturn on_configure(
59 const rclcpp_lifecycle::State & previous_state)
override;
61 controller_interface::CallbackReturn on_activate(
62 const rclcpp_lifecycle::State & previous_state)
override;
64 controller_interface::CallbackReturn on_deactivate(
65 const rclcpp_lifecycle::State & previous_state)
override;
68 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
71 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
73 using ControllerAckermannReferenceMsg = ackermann_msgs::msg::AckermannDriveStamped;
74 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
75 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
76 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
77 using AckermannControllerState = control_msgs::msg::SteeringControllerStatus;
80 controller_interface::CallbackReturn set_interface_numbers(
81 size_t nr_state_itfs,
size_t nr_cmd_itfs,
size_t nr_ref_itfs);
83 std::shared_ptr<steering_controllers_library::ParamListener> param_listener_;
84 steering_controllers_library::Params params_;
87 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ =
nullptr;
88 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_ackermann_ =
nullptr;
90 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
95 rclcpp::Publisher<ControllerStateMsgOdom>::SharedPtr odom_s_publisher_;
96 rclcpp::Publisher<ControllerStateMsgTf>::SharedPtr tf_odom_s_publisher_;
98 std::unique_ptr<ControllerStatePublisherOdom> rt_odom_state_publisher_;
99 std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_;
109 AckermannControllerState published_state_;
112 rclcpp::Publisher<AckermannControllerState>::SharedPtr controller_s_publisher_;
113 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
116 size_t nr_state_itfs_;
123 double last_linear_velocity_ = 0.0;
124 double last_angular_velocity_ = 0.0;
126 std::vector<std::string> rear_wheels_state_names_;
127 std::vector<std::string> front_wheels_state_names_;
131 void reference_callback(
const std::shared_ptr<ControllerTwistReferenceMsg> msg);
controller_interface::return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period) override
Execute calculations of the controller and update command interfaces.
Definition steering_controllers_library.cpp:369
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period) override
Update reference from input topics when not in chained mode.
Definition steering_controllers_library.cpp:355