ros2_control - rolling
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 "control_msgs/srv/set_odometry.hpp"
23#include "controller_interface/chainable_controller_interface.hpp"
24#include "geometry_msgs/msg/twist_stamped.hpp"
25#include "nav_msgs/msg/odometry.hpp"
26#include "omni_wheel_drive_controller/odometry.hpp"
27#include "realtime_tools/realtime_publisher.hpp"
28#include "realtime_tools/realtime_thread_safe_box.hpp"
29#include "tf2_msgs/msg/tf_message.hpp"
30
31// auto-generated by generate_parameter_library
32#include "omni_wheel_drive_controller/omni_wheel_drive_controller_parameters.hpp"
33
34namespace omni_wheel_drive_controller
35{
37{
38 using TwistStamped = geometry_msgs::msg::TwistStamped;
39
40public:
42
43 controller_interface::CallbackReturn on_init() override;
44
46
48
49 controller_interface::CallbackReturn on_configure(
50 const rclcpp_lifecycle::State & previous_state) override;
51
52 controller_interface::CallbackReturn on_activate(
53 const rclcpp_lifecycle::State & previous_state) override;
54
55 controller_interface::CallbackReturn on_deactivate(
56 const rclcpp_lifecycle::State & previous_state) override;
57
58 controller_interface::return_type update_reference_from_subscribers(
59 const rclcpp::Time & time, const rclcpp::Duration & period) override;
60
61 controller_interface::return_type update_and_write_commands(
62 const rclcpp::Time & time, const rclcpp::Duration & period) override;
63
64 controller_interface::CallbackReturn on_cleanup(
65 const rclcpp_lifecycle::State & previous_state) override;
66
67 controller_interface::CallbackReturn on_error(
68 const rclcpp_lifecycle::State & previous_state) override;
69
70 void set_odometry(
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);
74
75protected:
76 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
77
78 // Parameters from ROS for omni_wheel_drive_controller
79 std::shared_ptr<ParamListener> param_listener_;
80 Params params_;
81
83 {
84 std::optional<std::reference_wrapper<const hardware_interface::LoanedStateInterface>> feedback;
85 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
86 };
87 std::vector<WheelHandle> registered_wheel_handles_;
88
89 controller_interface::CallbackReturn configure_wheel_handles(
90 const std::vector<std::string> & wheel_names, std::vector<WheelHandle> & registered_handles);
91
92 // Timeout to consider cmd_vel commands old
93 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
94
95 std::atomic_bool subscriber_is_active_ = false;
96 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
97 // Realtime container to exchange the reference from subscriber
99 // Save the last reference in case of unable to get value from box
100 TwistStamped command_msg_;
101
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_;
106
107 Odometry odometry_;
108
109 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
110 nullptr;
111 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
112 realtime_odometry_transform_publisher_;
113 geometry_msgs::msg::TransformStamped transform_;
114
115 void compute_and_set_wheel_velocities();
116 const char * feedback_type() const;
117 void halt();
118 bool reset();
119 bool on_set_chained_mode(bool chained_mode) override;
120
121 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
122 std::atomic<bool> set_odom_requested_{false};
124 requested_odom_params_;
125
126private:
127 void reset_buffers();
128};
129} // namespace omni_wheel_drive_controller
130
131#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:37
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition omni_wheel_drive_controller.cpp:219
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition omni_wheel_drive_controller.cpp:52
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
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition omni_wheel_drive_controller.cpp:229
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:579
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition omni_wheel_drive_controller.cpp:582
Definition realtime_thread_safe_box.hpp:68
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:68
Definition omni_wheel_drive_controller.hpp:83