Class OmniWheelDriveController

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public controller_interface::ChainableControllerInterface

Class Documentation

class OmniWheelDriveController : public controller_interface::ChainableControllerInterface

Public Functions

OmniWheelDriveController()
controller_interface::CallbackReturn on_init() override
controller_interface::InterfaceConfiguration command_interface_configuration() const override
controller_interface::InterfaceConfiguration state_interface_configuration() const override
controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period) override
controller_interface::return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period) override
controller_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &previous_state) override
controller_interface::CallbackReturn on_error(const rclcpp_lifecycle::State &previous_state) override

Protected Functions

std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override
controller_interface::CallbackReturn configure_wheel_handles(const std::vector<std::string> &wheel_names, std::vector<WheelHandle> &registered_handles)
void compute_and_set_wheel_velocities()
const char *feedback_type() const
void halt()
bool reset()
bool on_set_chained_mode(bool chained_mode) override

Protected Attributes

std::shared_ptr<ParamListener> param_listener_
Params params_
std::vector<WheelHandle> registered_wheel_handles_
rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5)
std::atomic_bool subscriber_is_active_ = false
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr
realtime_tools::RealtimeThreadSafeBox<TwistStamped> received_velocity_msg_
TwistStamped command_msg_
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_
nav_msgs::msg::Odometry odometry_message_
Odometry odometry_
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_
geometry_msgs::msg::TransformStamped transform_
struct WheelHandle

Public Members

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