15 #ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_CONTROLLERS_LIBRARY_HPP_
16 #define STEERING_CONTROLLERS_LIBRARY__STEERING_CONTROLLERS_LIBRARY_HPP_
23 #include "controller_interface/chainable_controller_interface.hpp"
24 #include "hardware_interface/handle.hpp"
25 #include "rclcpp_lifecycle/state.hpp"
26 #include "realtime_tools/realtime_buffer.hpp"
27 #include "realtime_tools/realtime_publisher.hpp"
28 #include "steering_controllers_library/steering_odometry.hpp"
29 #include "steering_controllers_library/visibility_control.h"
30 #include "steering_controllers_library_parameters.hpp"
33 #include "ackermann_msgs/msg/ackermann_drive_stamped.hpp"
34 #include "control_msgs/msg/steering_controller_status.hpp"
35 #include "geometry_msgs/msg/twist_stamped.hpp"
36 #include "nav_msgs/msg/odometry.hpp"
37 #include "tf2_msgs/msg/tf_message.hpp"
39 namespace steering_controllers_library
46 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC
void
47 initialize_implementation_parameter_listener() = 0;
49 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn
on_init()
override;
57 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn
58 configure_odometry() = 0;
60 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC
bool update_odometry(
61 const rclcpp::Duration & period) = 0;
63 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure(
64 const rclcpp_lifecycle::State & previous_state)
override;
66 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate(
67 const rclcpp_lifecycle::State & previous_state)
override;
69 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate(
70 const rclcpp_lifecycle::State & previous_state)
override;
72 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
74 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
76 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
79 using ControllerAckermannReferenceMsg = ackermann_msgs::msg::AckermannDriveStamped;
80 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
81 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
82 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
83 using AckermanControllerState = control_msgs::msg::SteeringControllerStatus;
86 controller_interface::CallbackReturn set_interface_numbers(
87 size_t nr_state_itfs,
size_t nr_cmd_itfs,
size_t nr_ref_itfs);
89 std::shared_ptr<steering_controllers_library::ParamListener> param_listener_;
90 steering_controllers_library::Params params_;
93 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ =
nullptr;
94 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_ackermann_ =
nullptr;
96 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
101 rclcpp::Publisher<ControllerStateMsgOdom>::SharedPtr odom_s_publisher_;
102 rclcpp::Publisher<ControllerStateMsgTf>::SharedPtr tf_odom_s_publisher_;
104 std::unique_ptr<ControllerStatePublisherOdom> rt_odom_state_publisher_;
105 std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_;
115 AckermanControllerState published_state_;
118 rclcpp::Publisher<AckermanControllerState>::SharedPtr controller_s_publisher_;
119 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
122 size_t nr_state_itfs_;
129 double last_linear_velocity_ = 0.0;
130 double last_angular_velocity_ = 0.0;
132 std::vector<std::string> rear_wheels_state_names_;
133 std::vector<std::string> front_wheels_state_names_;
137 STEERING_CONTROLLERS__VISIBILITY_LOCAL
void reference_callback(
138 const std::shared_ptr<ControllerTwistReferenceMsg> msg);
Definition: chainable_controller_interface.hpp:38
Definition: steering_controllers_library.hpp:42
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition: steering_controllers_library.cpp:232
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition: steering_controllers_library.cpp:312
bool on_set_chained_mode(bool chained_mode) override
Virtual method that each chainable controller should implement to switch chained mode.
Definition: steering_controllers_library.cpp:330
STEERING_CONTROLLERS__VISIBILITY_PUBLIC 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
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition: steering_controllers_library.cpp:55
STEERING_CONTROLLERS__VISIBILITY_PUBLIC 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
steering_odometry::SteeringOdometry odometry_
Odometry:
Definition: steering_controllers_library.hpp:113
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition: steering_controllers_library.cpp:270
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition: steering_odometry.hpp:47
Configuring what command/state interfaces to claim.
Definition: controller_interface_base.hpp:58