57 controller_interface::CallbackReturn
on_init()
override;
63 controller_interface::CallbackReturn on_configure(
64 const rclcpp_lifecycle::State & previous_state)
override;
66 controller_interface::CallbackReturn on_activate(
67 const rclcpp_lifecycle::State & previous_state)
override;
69 controller_interface::CallbackReturn on_deactivate(
70 const rclcpp_lifecycle::State & previous_state)
override;
75 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
78 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
81 const std::shared_ptr<rmw_request_id_t> request_header,
82 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
83 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
85 using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped;
86 using OdomStateMsg = nav_msgs::msg::Odometry;
87 using TfStateMsg = tf2_msgs::msg::TFMessage;
88 using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState;
91 std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_;
92 mecanum_drive_controller::Params params_;
124 ControllerReferenceMsg current_ref_;
126 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
129 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ =
nullptr;
132 rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_;
133 std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_;
134 OdomStateMsg odom_state_msg_;
137 rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_;
138 std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_;
139 TfStateMsg tf_odom_state_msg_;
142 rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_;
143 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
144 ControllerStateMsg controller_state_msg_;
152 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
153 std::atomic<bool> set_odom_requested_{
false};
155 requested_odom_params_;
159 void reference_callback(
const std::shared_ptr<ControllerReferenceMsg> msg);
161 double velocity_in_center_frame_linear_x_;
162 double velocity_in_center_frame_linear_y_;
163 double velocity_in_center_frame_angular_z_;
166 std::unique_ptr<control_toolbox::RateLimiter<double>> limiter_linear_x_;
167 std::unique_ptr<control_toolbox::RateLimiter<double>> limiter_linear_y_;
168 std::unique_ptr<control_toolbox::RateLimiter<double>> limiter_angular_z_;
172 std::queue<std::array<double, 3>> previous_two_commands_;
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:510
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 mecanum_drive_controller.cpp:457