45 virtual void initialize_implementation_parameter_listener() = 0;
47 controller_interface::CallbackReturn
on_init()
override;
53 virtual controller_interface::CallbackReturn configure_odometry() = 0;
55 virtual bool update_odometry(
const rclcpp::Duration & period) = 0;
57 controller_interface::CallbackReturn on_configure(
58 const rclcpp_lifecycle::State & previous_state)
override;
60 controller_interface::CallbackReturn on_activate(
61 const rclcpp_lifecycle::State & previous_state)
override;
63 controller_interface::CallbackReturn on_deactivate(
64 const rclcpp_lifecycle::State & previous_state)
override;
67 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
70 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
72 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
73 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
74 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
75 using SteeringControllerStateMsg = control_msgs::msg::SteeringControllerStatus;
78 controller_interface::CallbackReturn set_interface_numbers(
79 size_t nr_state_itfs,
size_t nr_cmd_itfs,
size_t nr_ref_itfs);
81 std::shared_ptr<steering_controllers_library::ParamListener> param_listener_;
82 steering_controllers_library::Params params_;
87 ControllerTwistReferenceMsg current_ref_;
88 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
91 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ =
nullptr;
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 SteeringControllerStateMsg published_state_;
112 rclcpp::Publisher<SteeringControllerStateMsg>::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> traction_joints_state_names_;
127 std::vector<std::string> steering_joints_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:513
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:468