52 using Twist = geometry_msgs::msg::TwistStamped;
55 DIFF_DRIVE_CONTROLLER_PUBLIC
58 DIFF_DRIVE_CONTROLLER_PUBLIC
61 DIFF_DRIVE_CONTROLLER_PUBLIC
64 DIFF_DRIVE_CONTROLLER_PUBLIC
65 controller_interface::return_type
update(
66 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
68 DIFF_DRIVE_CONTROLLER_PUBLIC
69 controller_interface::CallbackReturn
on_init()
override;
71 DIFF_DRIVE_CONTROLLER_PUBLIC
72 controller_interface::CallbackReturn on_configure(
73 const rclcpp_lifecycle::State & previous_state)
override;
75 DIFF_DRIVE_CONTROLLER_PUBLIC
76 controller_interface::CallbackReturn on_activate(
77 const rclcpp_lifecycle::State & previous_state)
override;
79 DIFF_DRIVE_CONTROLLER_PUBLIC
80 controller_interface::CallbackReturn on_deactivate(
81 const rclcpp_lifecycle::State & previous_state)
override;
83 DIFF_DRIVE_CONTROLLER_PUBLIC
84 controller_interface::CallbackReturn on_cleanup(
85 const rclcpp_lifecycle::State & previous_state)
override;
87 DIFF_DRIVE_CONTROLLER_PUBLIC
88 controller_interface::CallbackReturn on_error(
89 const rclcpp_lifecycle::State & previous_state)
override;
91 DIFF_DRIVE_CONTROLLER_PUBLIC
92 controller_interface::CallbackReturn on_shutdown(
93 const rclcpp_lifecycle::State & previous_state)
override;
98 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
99 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
102 const char * feedback_type()
const;
103 controller_interface::CallbackReturn configure_side(
104 const std::string & side,
const std::vector<std::string> & wheel_names,
105 std::vector<WheelHandle> & registered_handles);
107 std::vector<WheelHandle> registered_left_wheel_handles_;
108 std::vector<WheelHandle> registered_right_wheel_handles_;
111 std::shared_ptr<ParamListener> param_listener_;
118 int wheels_per_side_;
123 std::chrono::milliseconds cmd_vel_timeout_{500};
125 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
126 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
127 realtime_odometry_publisher_ =
nullptr;
129 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
131 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
132 realtime_odometry_transform_publisher_ =
nullptr;
134 bool subscriber_is_active_ =
false;
135 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ =
nullptr;
136 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
137 velocity_command_unstamped_subscriber_ =
nullptr;
141 std::queue<Twist> previous_commands_;
144 SpeedLimiter limiter_linear_;
145 SpeedLimiter limiter_angular_;
147 bool publish_limited_velocity_ =
false;
148 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ =
nullptr;
149 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
152 rclcpp::Time previous_update_timestamp_{0};
155 double publish_rate_ = 50.0;
156 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
157 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
159 bool is_halted =
false;
160 bool use_stamped_vel_ =
true;