52 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC
void
53 initialize_implementation_parameter_listener() = 0;
55 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn
on_init()
override;
63 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn
64 configure_odometry() = 0;
66 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC
bool update_odometry(
67 const rclcpp::Duration & period) = 0;
69 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure(
70 const rclcpp_lifecycle::State & previous_state)
override;
72 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate(
73 const rclcpp_lifecycle::State & previous_state)
override;
75 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
81 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
84 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
85 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
86 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
87 using SteeringControllerStateMsg = control_msgs::msg::SteeringControllerStatus;
88 using AckermannControllerState [[deprecated]] =
89 SteeringControllerStateMsg;
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_;
99 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ =
nullptr;
100 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_ackermann_ =
102 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr ref_subscriber_unstamped_ =
nullptr;
104 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
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 std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_;
123 SteeringControllerStateMsg published_state_;
126 rclcpp::Publisher<SteeringControllerStateMsg>::SharedPtr controller_s_publisher_;
127 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
130 size_t nr_state_itfs_;
137 double last_linear_velocity_ = 0.0;
138 double last_angular_velocity_ = 0.0;
140 std::vector<std::string> rear_wheels_state_names_;
141 std::vector<std::string> front_wheels_state_names_;
145 STEERING_CONTROLLERS__VISIBILITY_LOCAL
void reference_callback(
146 const std::shared_ptr<ControllerTwistReferenceMsg> msg);
147 void reference_callback_unstamped(
const std::shared_ptr<geometry_msgs::msg::Twist> msg);
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:411