37 using TwistStamped = geometry_msgs::msg::TwistStamped;
42 controller_interface::CallbackReturn
on_init()
override;
48 controller_interface::CallbackReturn on_configure(
49 const rclcpp_lifecycle::State & previous_state)
override;
51 controller_interface::CallbackReturn on_activate(
52 const rclcpp_lifecycle::State & previous_state)
override;
54 controller_interface::CallbackReturn on_deactivate(
55 const rclcpp_lifecycle::State & previous_state)
override;
58 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
61 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
63 controller_interface::CallbackReturn on_cleanup(
64 const rclcpp_lifecycle::State & previous_state)
override;
66 controller_interface::CallbackReturn on_error(
67 const rclcpp_lifecycle::State & previous_state)
override;
73 std::shared_ptr<ParamListener> param_listener_;
78 std::optional<std::reference_wrapper<const hardware_interface::LoanedStateInterface>> feedback;
79 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
81 std::vector<WheelHandle> registered_wheel_handles_;
83 controller_interface::CallbackReturn configure_wheel_handles(
84 const std::vector<std::string> & wheel_names, std::vector<WheelHandle> & registered_handles);
87 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
89 std::atomic_bool subscriber_is_active_ =
false;
90 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
94 TwistStamped command_msg_;
96 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
97 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
98 realtime_odometry_publisher_;
99 nav_msgs::msg::Odometry odometry_message_;
103 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
105 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
106 realtime_odometry_transform_publisher_;
107 geometry_msgs::msg::TransformStamped transform_;
109 void compute_and_set_wheel_velocities();
110 const char * feedback_type()
const;
116 void reset_buffers();
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 omni_wheel_drive_controller.cpp:252
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 omni_wheel_drive_controller.cpp:290