ros2_control - rolling
Loading...
Searching...
No Matches
mecanum_drive_controller.hpp
1// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
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 MECANUM_DRIVE_CONTROLLER__MECANUM_DRIVE_CONTROLLER_HPP_
16#define MECANUM_DRIVE_CONTROLLER__MECANUM_DRIVE_CONTROLLER_HPP_
17
18#include <atomic>
19#include <chrono>
20#include <cmath>
21#include <memory>
22#include <queue>
23#include <string>
24#include <utility>
25#include <vector>
26
27#include "control_msgs/msg/mecanum_drive_controller_state.hpp"
28#include "control_msgs/srv/set_odometry.hpp"
29#include "control_toolbox/rate_limiter.hpp"
30#include "controller_interface/chainable_controller_interface.hpp"
31#include "geometry_msgs/msg/twist_stamped.hpp"
32#include "nav_msgs/msg/odometry.hpp"
33#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
34#include "rclcpp_lifecycle/state.hpp"
35#include "realtime_tools/realtime_publisher.hpp"
36#include "realtime_tools/realtime_thread_safe_box.hpp"
37#include "tf2_msgs/msg/tf_message.hpp"
38
39#include "mecanum_drive_controller/mecanum_drive_controller_parameters.hpp"
40#include "mecanum_drive_controller/odometry.hpp"
41namespace mecanum_drive_controller
42{
43// name constants for state interfaces
44static constexpr size_t NR_STATE_ITFS = 4;
45
46// name constants for command interfaces
47static constexpr size_t NR_CMD_ITFS = 4;
48
49// name constants for reference interfaces
50static constexpr size_t NR_REF_ITFS = 3;
51
53{
54public:
56
57 controller_interface::CallbackReturn on_init() override;
58
60
62
63 controller_interface::CallbackReturn on_configure(
64 const rclcpp_lifecycle::State & previous_state) override;
65
66 controller_interface::CallbackReturn on_activate(
67 const rclcpp_lifecycle::State & previous_state) override;
68
69 controller_interface::CallbackReturn on_deactivate(
70 const rclcpp_lifecycle::State & previous_state) override;
71
72 void reset_buffers();
73
74 controller_interface::return_type update_reference_from_subscribers(
75 const rclcpp::Time & time, const rclcpp::Duration & period) override;
76
77 controller_interface::return_type update_and_write_commands(
78 const rclcpp::Time & time, const rclcpp::Duration & period) override;
79
80 void set_odometry(
81 const std::shared_ptr<rmw_request_id_t> request_header,
82 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
83 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
84
85 using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped;
86 using OdomStateMsg = nav_msgs::msg::Odometry;
87 using TfStateMsg = tf2_msgs::msg::TFMessage;
88 using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState;
89
90protected:
91 std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_;
92 mecanum_drive_controller::Params params_;
93
101 enum WheelIndex : std::size_t
102 {
103 FRONT_LEFT = 0,
104 FRONT_RIGHT = 1,
105 REAR_RIGHT = 2,
106 REAR_LEFT = 3
107 };
108
112 std::vector<std::string> command_joint_names_;
113
119 std::vector<std::string> state_joint_names_;
120
121 // the RT Box containing the command message
123 // save the last reference in case of unable to get value from box
124 ControllerReferenceMsg current_ref_;
125 // the reference timeout value from parameters
126 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
127
128 // Command subscribers and Controller State, odom state, tf state publishers
129 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
130
132 rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_;
133 std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_;
134 OdomStateMsg odom_state_msg_;
135
137 rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_;
138 std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_;
139 TfStateMsg tf_odom_state_msg_;
140
142 rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_;
143 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
144 ControllerStateMsg controller_state_msg_;
145
146 // override methods from ChainableControllerInterface
147 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
148
149 bool on_set_chained_mode(bool chained_mode) override;
150
151 Odometry odometry_;
152 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
153 std::atomic<bool> set_odom_requested_{false};
155 requested_odom_params_;
156
157private:
158 // callback for topic interface
159 void reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg);
160
161 double velocity_in_center_frame_linear_x_; // [m/s]
162 double velocity_in_center_frame_linear_y_; // [m/s]
163 double velocity_in_center_frame_angular_z_; // [rad/s]
164
165 // Speed limiters
166 std::unique_ptr<control_toolbox::RateLimiter<double>> limiter_linear_x_;
167 std::unique_ptr<control_toolbox::RateLimiter<double>> limiter_linear_y_;
168 std::unique_ptr<control_toolbox::RateLimiter<double>> limiter_angular_z_;
169
170protected:
171 // Previous two commands for jerk limiting: queue of [linear_x, linear_y, angular_z]
172 std::queue<std::array<double, 3>> previous_two_commands_;
173};
174
175} // namespace mecanum_drive_controller
176
177#endif // MECANUM_DRIVE_CONTROLLER__MECANUM_DRIVE_CONTROLLER_HPP_
Virtual class to implement when integrating a controller that can be preceded by other controllers.
Definition chainable_controller_interface.hpp:38
Definition mecanum_drive_controller.hpp:53
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition mecanum_drive_controller.cpp:59
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:510
WheelIndex
Definition mecanum_drive_controller.hpp:102
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:457
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition mecanum_drive_controller.cpp:369
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition mecanum_drive_controller.cpp:355
std::vector< std::string > command_joint_names_
Definition mecanum_drive_controller.hpp:112
bool on_set_chained_mode(bool chained_mode) override
Virtual method that each chainable controller should implement to switch chained mode.
Definition mecanum_drive_controller.cpp:407
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Virtual method implemented by chainable controllers to export read/write interfaces.
Definition mecanum_drive_controller.cpp:386
std::vector< std::string > state_joint_names_
Definition mecanum_drive_controller.hpp:119
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition odometry.hpp:30
Definition realtime_publisher.hpp:55
Definition realtime_thread_safe_box.hpp:68
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:72