50 using Twist = geometry_msgs::msg::TwistStamped;
53 DIFF_DRIVE_CONTROLLER_PUBLIC
56 DIFF_DRIVE_CONTROLLER_PUBLIC
59 DIFF_DRIVE_CONTROLLER_PUBLIC
62 DIFF_DRIVE_CONTROLLER_PUBLIC
63 controller_interface::return_type
update(
64 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
66 DIFF_DRIVE_CONTROLLER_PUBLIC
67 controller_interface::CallbackReturn
on_init()
override;
69 DIFF_DRIVE_CONTROLLER_PUBLIC
70 controller_interface::CallbackReturn on_configure(
71 const rclcpp_lifecycle::State & previous_state)
override;
73 DIFF_DRIVE_CONTROLLER_PUBLIC
74 controller_interface::CallbackReturn on_activate(
75 const rclcpp_lifecycle::State & previous_state)
override;
77 DIFF_DRIVE_CONTROLLER_PUBLIC
78 controller_interface::CallbackReturn on_deactivate(
79 const rclcpp_lifecycle::State & previous_state)
override;
81 DIFF_DRIVE_CONTROLLER_PUBLIC
82 controller_interface::CallbackReturn on_cleanup(
83 const rclcpp_lifecycle::State & previous_state)
override;
85 DIFF_DRIVE_CONTROLLER_PUBLIC
86 controller_interface::CallbackReturn on_error(
87 const rclcpp_lifecycle::State & previous_state)
override;
89 DIFF_DRIVE_CONTROLLER_PUBLIC
90 controller_interface::CallbackReturn on_shutdown(
91 const rclcpp_lifecycle::State & previous_state)
override;
96 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
97 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
100 const char * feedback_type()
const;
101 controller_interface::CallbackReturn configure_side(
102 const std::string & side,
const std::vector<std::string> & wheel_names,
103 std::vector<WheelHandle> & registered_handles);
105 std::vector<WheelHandle> registered_left_wheel_handles_;
106 std::vector<WheelHandle> registered_right_wheel_handles_;
109 std::shared_ptr<ParamListener> param_listener_;
115 std::chrono::milliseconds cmd_vel_timeout_{500};
117 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
118 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
119 realtime_odometry_publisher_ =
nullptr;
121 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
123 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
124 realtime_odometry_transform_publisher_ =
nullptr;
126 bool subscriber_is_active_ =
false;
127 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ =
nullptr;
128 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
129 velocity_command_unstamped_subscriber_ =
nullptr;
133 std::queue<Twist> previous_commands_;
136 SpeedLimiter limiter_linear_;
137 SpeedLimiter limiter_angular_;
139 bool publish_limited_velocity_ =
false;
140 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ =
nullptr;
141 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
144 rclcpp::Time previous_update_timestamp_{0};
147 double publish_rate_ = 50.0;
148 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
149 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
151 bool is_halted =
false;
152 bool use_stamped_vel_ =
true;