55 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
58 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
59 controller_interface::CallbackReturn
on_init()
override;
61 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
64 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
67 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
68 controller_interface::CallbackReturn on_configure(
69 const rclcpp_lifecycle::State & previous_state)
override;
71 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
72 controller_interface::CallbackReturn on_activate(
73 const rclcpp_lifecycle::State & previous_state)
override;
75 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
76 controller_interface::CallbackReturn on_deactivate(
77 const rclcpp_lifecycle::State & previous_state)
override;
79 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
82 MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC
84 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
86 using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped;
87 using ControllerReferenceMsgUnstamped = geometry_msgs::msg::Twist;
88 using OdomStateMsg = nav_msgs::msg::Odometry;
89 using TfStateMsg = tf2_msgs::msg::TFMessage;
90 using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState;
93 std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_;
94 mecanum_drive_controller::Params params_;
125 std::vector<std::string> reference_names_;
128 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ =
nullptr;
129 rclcpp::Subscription<ControllerReferenceMsgUnstamped>::SharedPtr ref_unstamped_subscriber_ =
132 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
135 rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_;
136 std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_;
139 rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_;
140 std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_;
143 rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_;
144 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
153 bool use_stamped_vel_ =
true;
157 MECANUM_DRIVE_CONTROLLER__VISIBILITY_LOCAL
158 void reference_callback(
const std::shared_ptr<ControllerReferenceMsg> msg);
159 MECANUM_DRIVE_CONTROLLER__VISIBILITY_LOCAL
160 void reference_unstamped_callback(
const std::shared_ptr<ControllerReferenceMsgUnstamped> msg);
162 double velocity_in_center_frame_linear_x_;
163 double velocity_in_center_frame_linear_y_;
164 double velocity_in_center_frame_angular_z_;
MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition mecanum_drive_controller.cpp:59
MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC 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 mecanum_drive_controller.cpp:353
MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition mecanum_drive_controller.cpp:287
MECANUM_DRIVE_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition mecanum_drive_controller.cpp:273