46 using TwistStamped = geometry_msgs::msg::TwistStamped;
57 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
60 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
62 controller_interface::CallbackReturn
on_init()
override;
64 controller_interface::CallbackReturn on_configure(
65 const rclcpp_lifecycle::State & previous_state)
override;
67 controller_interface::CallbackReturn on_activate(
68 const rclcpp_lifecycle::State & previous_state)
override;
70 controller_interface::CallbackReturn on_deactivate(
71 const rclcpp_lifecycle::State & previous_state)
override;
73 controller_interface::CallbackReturn on_cleanup(
74 const rclcpp_lifecycle::State & previous_state)
override;
76 controller_interface::CallbackReturn on_error(
77 const rclcpp_lifecycle::State & previous_state)
override;
86 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
87 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
90 const char * feedback_type()
const;
91 controller_interface::CallbackReturn configure_side(
92 const std::string & side,
const std::vector<std::string> & wheel_names,
93 std::vector<WheelHandle> & registered_handles);
95 std::vector<WheelHandle> registered_left_wheel_handles_;
96 std::vector<WheelHandle> registered_right_wheel_handles_;
99 std::shared_ptr<ParamListener> param_listener_;
106 int wheels_per_side_;
111 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
113 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
114 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
115 realtime_odometry_publisher_ =
nullptr;
117 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
119 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
120 realtime_odometry_transform_publisher_ =
nullptr;
122 bool subscriber_is_active_ =
false;
123 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
127 std::queue<std::array<double, 2>> previous_two_commands_;
129 std::unique_ptr<SpeedLimiter> limiter_linear_;
130 std::unique_ptr<SpeedLimiter> limiter_angular_;
132 bool publish_limited_velocity_ =
false;
133 std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ =
nullptr;
134 std::shared_ptr<realtime_tools::RealtimePublisher<TwistStamped>>
135 realtime_limited_velocity_publisher_ =
nullptr;
137 rclcpp::Time previous_update_timestamp_{0};
140 double publish_rate_ = 50.0;
141 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
142 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
144 bool is_halted =
false;
150 void reset_buffers();
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period) override
Update reference from input topics when not in chained mode.
Definition diff_drive_controller.cpp:100
controller_interface::return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period) override
Execute calculations of the controller and update command interfaces.
Definition diff_drive_controller.cpp:148