51 using Twist = geometry_msgs::msg::TwistStamped;
54 DIFF_DRIVE_CONTROLLER_PUBLIC
57 DIFF_DRIVE_CONTROLLER_PUBLIC
60 DIFF_DRIVE_CONTROLLER_PUBLIC
63 DIFF_DRIVE_CONTROLLER_PUBLIC
64 controller_interface::return_type
update(
65 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
67 DIFF_DRIVE_CONTROLLER_PUBLIC
68 controller_interface::CallbackReturn
on_init()
override;
70 DIFF_DRIVE_CONTROLLER_PUBLIC
71 controller_interface::CallbackReturn on_configure(
72 const rclcpp_lifecycle::State & previous_state)
override;
74 DIFF_DRIVE_CONTROLLER_PUBLIC
75 controller_interface::CallbackReturn on_activate(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 DIFF_DRIVE_CONTROLLER_PUBLIC
79 controller_interface::CallbackReturn on_deactivate(
80 const rclcpp_lifecycle::State & previous_state)
override;
82 DIFF_DRIVE_CONTROLLER_PUBLIC
83 controller_interface::CallbackReturn on_cleanup(
84 const rclcpp_lifecycle::State & previous_state)
override;
86 DIFF_DRIVE_CONTROLLER_PUBLIC
87 controller_interface::CallbackReturn on_error(
88 const rclcpp_lifecycle::State & previous_state)
override;
93 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_;
112 std::chrono::milliseconds cmd_vel_timeout_{500};
114 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
115 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
116 realtime_odometry_publisher_ =
nullptr;
118 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
120 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
121 realtime_odometry_transform_publisher_ =
nullptr;
123 bool subscriber_is_active_ =
false;
124 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ =
nullptr;
125 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
126 velocity_command_unstamped_subscriber_ =
nullptr;
130 std::queue<Twist> previous_commands_;
133 SpeedLimiter limiter_linear_;
134 SpeedLimiter limiter_angular_;
136 bool publish_limited_velocity_ =
false;
137 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ =
nullptr;
138 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
141 rclcpp::Time previous_update_timestamp_{0};
144 double publish_rate_ = 50.0;
145 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
146 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
148 bool is_halted =
false;
149 bool use_stamped_vel_ =
true;