51 using Twist = geometry_msgs::msg::TwistStamped;
54 DIFF_DRIVE_CONTROLLER_PUBLIC
57 DIFF_DRIVE_CONTROLLER_PUBLIC
58 controller_interface::return_type init(
const std::string & controller_name)
override;
60 DIFF_DRIVE_CONTROLLER_PUBLIC
63 DIFF_DRIVE_CONTROLLER_PUBLIC
66 DIFF_DRIVE_CONTROLLER_PUBLIC
67 controller_interface::return_type update()
override;
69 DIFF_DRIVE_CONTROLLER_PUBLIC
70 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
72 DIFF_DRIVE_CONTROLLER_PUBLIC
73 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
75 DIFF_DRIVE_CONTROLLER_PUBLIC
76 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
78 DIFF_DRIVE_CONTROLLER_PUBLIC
79 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
81 DIFF_DRIVE_CONTROLLER_PUBLIC
82 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
84 DIFF_DRIVE_CONTROLLER_PUBLIC
85 CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state)
override;
90 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position;
91 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
94 CallbackReturn configure_side(
95 const std::string & side,
const std::vector<std::string> & wheel_names,
96 std::vector<WheelHandle> & registered_handles);
98 std::vector<std::string> left_wheel_names_;
99 std::vector<std::string> right_wheel_names_;
101 std::vector<WheelHandle> registered_left_wheel_handles_;
102 std::vector<WheelHandle> registered_right_wheel_handles_;
106 size_t wheels_per_side = 0;
107 double separation = 0.0;
109 double separation_multiplier = 1.0;
110 double left_radius_multiplier = 1.0;
111 double right_radius_multiplier = 1.0;
116 bool open_loop =
false;
117 bool enable_odom_tf =
true;
118 std::string base_frame_id =
"base_link";
119 std::string odom_frame_id =
"odom";
120 std::array<double, 6> pose_covariance_diagonal;
121 std::array<double, 6> twist_covariance_diagonal;
126 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
127 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
128 realtime_odometry_publisher_ =
nullptr;
130 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
132 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
133 realtime_odometry_transform_publisher_ =
nullptr;
136 std::chrono::milliseconds cmd_vel_timeout_{500};
138 bool subscriber_is_active_ =
false;
139 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ =
nullptr;
140 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
141 velocity_command_unstamped_subscriber_ =
nullptr;
145 std::queue<Twist> previous_commands_;
148 SpeedLimiter limiter_linear_;
149 SpeedLimiter limiter_angular_;
151 bool publish_limited_velocity_ =
false;
152 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ =
nullptr;
153 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
156 rclcpp::Time previous_update_timestamp_{0};
159 double publish_rate_ = 50.0;
160 rclcpp::Duration publish_period_{0, 0};
161 rclcpp::Time previous_publish_timestamp_{0};
163 bool is_halted =
false;
164 bool use_stamped_vel_ =
true;