ros2_control - jazzy
Loading...
Searching...
No Matches
omni_wheel_drive_controller.hpp
1// Copyright 2025 Aarav Gupta
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef OMNI_WHEEL_DRIVE_CONTROLLER__OMNI_WHEEL_DRIVE_CONTROLLER_HPP_
16#define OMNI_WHEEL_DRIVE_CONTROLLER__OMNI_WHEEL_DRIVE_CONTROLLER_HPP_
17
18#include <memory>
19#include <string>
20#include <vector>
21
22#include "controller_interface/chainable_controller_interface.hpp"
23#include "geometry_msgs/msg/twist_stamped.hpp"
24#include "nav_msgs/msg/odometry.hpp"
25#include "omni_wheel_drive_controller/odometry.hpp"
26#include "realtime_tools/realtime_publisher.hpp"
27#include "realtime_tools/realtime_thread_safe_box.hpp"
28#include "tf2_msgs/msg/tf_message.hpp"
29
30// auto-generated by generate_parameter_library
31#include "omni_wheel_drive_controller/omni_wheel_drive_controller_parameters.hpp"
32
33namespace omni_wheel_drive_controller
34{
36{
37 using TwistStamped = geometry_msgs::msg::TwistStamped;
38
39public:
41
42 controller_interface::CallbackReturn on_init() override;
43
45
47
48 controller_interface::CallbackReturn on_configure(
49 const rclcpp_lifecycle::State & previous_state) override;
50
51 controller_interface::CallbackReturn on_activate(
52 const rclcpp_lifecycle::State & previous_state) override;
53
54 controller_interface::CallbackReturn on_deactivate(
55 const rclcpp_lifecycle::State & previous_state) override;
56
57 controller_interface::return_type update_reference_from_subscribers(
58 const rclcpp::Time & time, const rclcpp::Duration & period) override;
59
60 controller_interface::return_type update_and_write_commands(
61 const rclcpp::Time & time, const rclcpp::Duration & period) override;
62
63 controller_interface::CallbackReturn on_cleanup(
64 const rclcpp_lifecycle::State & previous_state) override;
65
66 controller_interface::CallbackReturn on_error(
67 const rclcpp_lifecycle::State & previous_state) override;
68
69protected:
70 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
71
72 // Parameters from ROS for omni_wheel_drive_controller
73 std::shared_ptr<ParamListener> param_listener_;
74 Params params_;
75
77 {
78 std::optional<std::reference_wrapper<const hardware_interface::LoanedStateInterface>> feedback;
79 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
80 };
81 std::vector<WheelHandle> registered_wheel_handles_;
82
83 controller_interface::CallbackReturn configure_wheel_handles(
84 const std::vector<std::string> & wheel_names, std::vector<WheelHandle> & registered_handles);
85
86 // Timeout to consider cmd_vel commands old
87 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
88
89 std::atomic_bool subscriber_is_active_ = false;
90 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
91 // Realtime container to exchange the reference from subscriber
93 // Save the last reference in case of unable to get value from box
94 TwistStamped command_msg_;
95
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_;
100
101 Odometry odometry_;
102
103 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
104 nullptr;
105 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
106 realtime_odometry_transform_publisher_;
107 geometry_msgs::msg::TransformStamped transform_;
108
109 void compute_and_set_wheel_velocities();
110 const char * feedback_type() const;
111 void halt();
112 bool reset();
113 bool on_set_chained_mode(bool chained_mode) override;
114
115private:
116 void reset_buffers();
117};
118} // namespace omni_wheel_drive_controller
119
120#endif // OMNI_WHEEL_DRIVE_CONTROLLER__OMNI_WHEEL_DRIVE_CONTROLLER_HPP_
Definition chainable_controller_interface.hpp:37
Definition odometry.hpp:26
Definition omni_wheel_drive_controller.hpp:36
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition omni_wheel_drive_controller.cpp:195
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition omni_wheel_drive_controller.cpp:50
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
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition omni_wheel_drive_controller.cpp:205
bool on_set_chained_mode(bool chained_mode) override
Virtual method that each chainable controller should implement to switch chained mode.
Definition omni_wheel_drive_controller.cpp:517
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition omni_wheel_drive_controller.cpp:520
Definition realtime_thread_safe_box.hpp:68
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:58
Definition omni_wheel_drive_controller.hpp:77