Class DiffDriveController

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

class DiffDriveController : public controller_interface::ControllerInterface

Public Functions

DIFF_DRIVE_CONTROLLER_PUBLIC DiffDriveController()
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override

Protected Functions

const char *feedback_type() const
controller_interface::CallbackReturn configure_side(const std::string &side, const std::vector<std::string> &wheel_names, std::vector<WheelHandle> &registered_handles)
bool reset()
void halt()

Protected Attributes

std::vector<WheelHandle> registered_left_wheel_handles_
std::vector<WheelHandle> registered_right_wheel_handles_
std::shared_ptr<ParamListener> param_listener_
Params params_
Odometry odometry_
std::chrono::milliseconds cmd_vel_timeout_ = {500}
std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr
std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>> realtime_odometry_publisher_ = nullptr
std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ = nullptr
std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>> realtime_odometry_transform_publisher_ = nullptr
bool subscriber_is_active_ = false
rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr velocity_command_unstamped_subscriber_ = nullptr
realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_ = {nullptr}
std::queue<Twist> previous_commands_
SpeedLimiter limiter_linear_
SpeedLimiter limiter_angular_
bool publish_limited_velocity_ = false
std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr
std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ = nullptr
rclcpp::Time previous_update_timestamp_ = {0}
double publish_rate_ = 50.0
rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0)
rclcpp::Time previous_publish_timestamp_ = {0, 0, RCL_CLOCK_UNINITIALIZED}
bool is_halted = false
bool use_stamped_vel_ = true
struct WheelHandle

Public Members

std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback
std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity