48 using TwistStamped = geometry_msgs::msg::TwistStamped;
59 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
62 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
64 controller_interface::CallbackReturn
on_init()
override;
66 controller_interface::CallbackReturn on_configure(
67 const rclcpp_lifecycle::State & previous_state)
override;
69 controller_interface::CallbackReturn on_activate(
70 const rclcpp_lifecycle::State & previous_state)
override;
72 controller_interface::CallbackReturn on_deactivate(
73 const rclcpp_lifecycle::State & previous_state)
override;
75 controller_interface::CallbackReturn on_cleanup(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 controller_interface::CallbackReturn on_error(
79 const rclcpp_lifecycle::State & previous_state)
override;
82 const std::shared_ptr<rmw_request_id_t> request_header,
83 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
84 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
93 std::optional<std::reference_wrapper<const hardware_interface::LoanedStateInterface>> feedback;
94 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
97 const char * feedback_type()
const;
98 controller_interface::CallbackReturn configure_side(
99 const std::string & side,
const std::vector<std::string> & wheel_names,
100 std::vector<WheelHandle> & registered_handles);
102 std::vector<WheelHandle> registered_left_wheel_handles_;
103 std::vector<WheelHandle> registered_right_wheel_handles_;
106 std::shared_ptr<ParamListener> param_listener_;
113 int wheels_per_side_;
118 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
120 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
121 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
122 realtime_odometry_publisher_ =
nullptr;
123 nav_msgs::msg::Odometry odometry_message_;
125 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
127 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
128 realtime_odometry_transform_publisher_ =
nullptr;
129 tf2_msgs::msg::TFMessage odometry_transform_message_;
131 bool subscriber_is_active_ =
false;
132 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
137 TwistStamped command_msg_;
139 std::queue<std::array<double, 2>> previous_two_commands_;
141 std::unique_ptr<SpeedLimiter> limiter_linear_;
142 std::unique_ptr<SpeedLimiter> limiter_angular_;
144 bool publish_limited_velocity_ =
false;
145 std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ =
nullptr;
146 std::shared_ptr<realtime_tools::RealtimePublisher<TwistStamped>>
147 realtime_limited_velocity_publisher_ =
nullptr;
148 TwistStamped limited_velocity_message_;
150 rclcpp::Time previous_update_timestamp_{0};
153 double publish_rate_ = 50.0;
154 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
155 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
157 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
158 std::atomic<bool> set_odom_requested_{
false};
160 requested_odom_params_;
166 void reset_buffers();