56 controller_interface::CallbackReturn
on_init()
override;
62 controller_interface::CallbackReturn on_configure(
63 const rclcpp_lifecycle::State & previous_state)
override;
65 controller_interface::CallbackReturn on_activate(
66 const rclcpp_lifecycle::State & previous_state)
override;
68 controller_interface::CallbackReturn on_deactivate(
69 const rclcpp_lifecycle::State & previous_state)
override;
72 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
75 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
78 const std::shared_ptr<rmw_request_id_t> request_header,
79 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
80 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
82 using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped;
83 using OdomStateMsg = nav_msgs::msg::Odometry;
84 using TfStateMsg = tf2_msgs::msg::TFMessage;
85 using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState;
88 std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_;
89 mecanum_drive_controller::Params params_;
121 ControllerReferenceMsg current_ref_;
123 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
126 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ =
nullptr;
129 rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_;
130 std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_;
131 OdomStateMsg odom_state_msg_;
134 rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_;
135 std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_;
136 TfStateMsg tf_odom_state_msg_;
139 rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_;
140 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
141 ControllerStateMsg controller_state_msg_;
149 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
150 std::atomic<bool> set_odom_requested_{
false};
152 requested_odom_params_;
156 void reference_callback(
const std::shared_ptr<ControllerReferenceMsg> msg);
158 double velocity_in_center_frame_linear_x_;
159 double velocity_in_center_frame_linear_y_;
160 double velocity_in_center_frame_angular_z_;
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:445
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:392