38 using TwistStamped = geometry_msgs::msg::TwistStamped;
43 controller_interface::CallbackReturn
on_init()
override;
49 controller_interface::CallbackReturn on_configure(
50 const rclcpp_lifecycle::State & previous_state)
override;
52 controller_interface::CallbackReturn on_activate(
53 const rclcpp_lifecycle::State & previous_state)
override;
55 controller_interface::CallbackReturn on_deactivate(
56 const rclcpp_lifecycle::State & previous_state)
override;
59 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
62 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
64 controller_interface::CallbackReturn on_cleanup(
65 const rclcpp_lifecycle::State & previous_state)
override;
67 controller_interface::CallbackReturn on_error(
68 const rclcpp_lifecycle::State & previous_state)
override;
71 const std::shared_ptr<rmw_request_id_t> request_header,
72 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
73 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
79 std::shared_ptr<ParamListener> param_listener_;
84 std::optional<std::reference_wrapper<const hardware_interface::LoanedStateInterface>> feedback;
85 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
87 std::vector<WheelHandle> registered_wheel_handles_;
89 controller_interface::CallbackReturn configure_wheel_handles(
90 const std::vector<std::string> & wheel_names, std::vector<WheelHandle> & registered_handles);
93 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
95 std::atomic_bool subscriber_is_active_ =
false;
96 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
100 TwistStamped command_msg_;
102 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
103 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
104 realtime_odometry_publisher_;
105 nav_msgs::msg::Odometry odometry_message_;
109 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
111 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
112 realtime_odometry_transform_publisher_;
113 geometry_msgs::msg::TransformStamped transform_;
115 void compute_and_set_wheel_velocities();
116 const char * feedback_type()
const;
121 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
122 std::atomic<bool> set_odom_requested_{
false};
124 requested_odom_params_;
127 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:276
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:314