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 CallbackReturn on_init()
override;
70 DIFF_DRIVE_CONTROLLER_PUBLIC
71 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
73 DIFF_DRIVE_CONTROLLER_PUBLIC
74 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
76 DIFF_DRIVE_CONTROLLER_PUBLIC
77 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
79 DIFF_DRIVE_CONTROLLER_PUBLIC
80 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
82 DIFF_DRIVE_CONTROLLER_PUBLIC
83 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
85 DIFF_DRIVE_CONTROLLER_PUBLIC
86 CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state)
override;
91 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
92 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
95 const char * feedback_type()
const;
96 CallbackReturn configure_side(
97 const std::string & side,
const std::vector<std::string> & wheel_names,
98 std::vector<WheelHandle> & registered_handles);
100 std::vector<std::string> left_wheel_names_;
101 std::vector<std::string> right_wheel_names_;
103 std::vector<WheelHandle> registered_left_wheel_handles_;
104 std::vector<WheelHandle> registered_right_wheel_handles_;
108 size_t wheels_per_side = 0;
109 double separation = 0.0;
111 double separation_multiplier = 1.0;
112 double left_radius_multiplier = 1.0;
113 double right_radius_multiplier = 1.0;
118 bool open_loop =
false;
119 bool position_feedback =
true;
120 bool enable_odom_tf =
true;
121 std::string base_frame_id =
"base_link";
122 std::string odom_frame_id =
"odom";
123 std::array<double, 6> pose_covariance_diagonal;
124 std::array<double, 6> twist_covariance_diagonal;
129 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
130 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
131 realtime_odometry_publisher_ =
nullptr;
133 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
135 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
136 realtime_odometry_transform_publisher_ =
nullptr;
139 std::chrono::milliseconds cmd_vel_timeout_{500};
141 bool subscriber_is_active_ =
false;
142 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ =
nullptr;
143 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
144 velocity_command_unstamped_subscriber_ =
nullptr;
148 std::queue<Twist> previous_commands_;
151 SpeedLimiter limiter_linear_;
152 SpeedLimiter limiter_angular_;
154 bool publish_limited_velocity_ =
false;
155 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ =
nullptr;
156 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
159 rclcpp::Time previous_update_timestamp_{0};
162 double publish_rate_ = 50.0;
163 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
164 rclcpp::Time previous_publish_timestamp_{0};
166 bool is_halted =
false;
167 bool use_stamped_vel_ =
true;