Class MecanumDriveController
Defined in File mecanum_drive_controller.hpp
Inheritance Relationships
Base Type
public controller_interface::ChainableControllerInterface
Class Documentation
-
class MecanumDriveController : public controller_interface::ChainableControllerInterface
Public Types
-
using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped
-
using OdomStateMsg = nav_msgs::msg::Odometry
-
using TfStateMsg = tf2_msgs::msg::TFMessage
-
using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState
Public Functions
-
MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC MecanumDriveController()
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init () override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::return_type update_reference_from_subscribers (const rclcpp::Time &time, const rclcpp::Duration &period) override
- MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::return_type update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period) override
Protected Types
-
enum WheelIndex
The list is sorted in the following order:
front left wheel
front right wheel
back right wheel
back left wheel
Values:
-
enumerator FRONT_LEFT
-
enumerator FRONT_RIGHT
-
enumerator REAR_RIGHT
-
enumerator REAR_LEFT
-
using OdomStatePublisher = realtime_tools::RealtimePublisher<OdomStateMsg>
-
using TfStatePublisher = realtime_tools::RealtimePublisher<TfStateMsg>
-
using ControllerStatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>
Protected Functions
-
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override
-
bool on_set_chained_mode(bool chained_mode) override
Protected Attributes
-
std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_
-
mecanum_drive_controller::Params params_
-
std::vector<std::string> command_joint_names_
Internal lists with joint names sorted as in
WheelIndex
enum.
-
std::vector<std::string> state_joint_names_
Internal lists with joint names sorted as in
WheelIndex
enum. If parameters for state joint names are not defined, this list is the same ascommand_joint_names_
.
-
std::vector<std::string> reference_names_
-
rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr
-
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerReferenceMsg>> input_ref_
-
rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0)
-
rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_
-
std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_
-
rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_
-
std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_
-
rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_
-
std::unique_ptr<ControllerStatePublisher> controller_state_publisher_
-
using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped