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 <chrono>
19#include <cmath>
20#include <memory>
21#include <queue>
22#include <string>
23#include <utility>
24#include <vector>
25
26#include "control_msgs/msg/mecanum_drive_controller_state.hpp"
27#include "controller_interface/chainable_controller_interface.hpp"
28#include "geometry_msgs/msg/twist_stamped.hpp"
29#include "nav_msgs/msg/odometry.hpp"
30#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
31#include "rclcpp_lifecycle/state.hpp"
32#include "realtime_tools/realtime_buffer.hpp"
33#include "realtime_tools/realtime_publisher.hpp"
34#include "std_srvs/srv/set_bool.hpp"
35#include "tf2_msgs/msg/tf_message.hpp"
36
37#include "mecanum_drive_controller/mecanum_drive_controller_parameters.hpp"
38#include "mecanum_drive_controller/odometry.hpp"
39namespace mecanum_drive_controller
40{
41// name constants for state interfaces
42static constexpr size_t NR_STATE_ITFS = 4;
43
44// name constants for command interfaces
45static constexpr size_t NR_CMD_ITFS = 4;
46
47// name constants for reference interfaces
48static constexpr size_t NR_REF_ITFS = 3;
49
51{
52public:
54
55 controller_interface::CallbackReturn on_init() override;
56
58
60
61 controller_interface::CallbackReturn on_configure(
62 const rclcpp_lifecycle::State & previous_state) override;
63
64 controller_interface::CallbackReturn on_activate(
65 const rclcpp_lifecycle::State & previous_state) override;
66
67 controller_interface::CallbackReturn on_deactivate(
68 const rclcpp_lifecycle::State & previous_state) override;
69
70 controller_interface::return_type update_reference_from_subscribers(
71 const rclcpp::Time & time, const rclcpp::Duration & period) override;
72
73 controller_interface::return_type update_and_write_commands(
74 const rclcpp::Time & time, const rclcpp::Duration & period) override;
75
76 using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped;
77 using OdomStateMsg = nav_msgs::msg::Odometry;
78 using TfStateMsg = tf2_msgs::msg::TFMessage;
79 using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState;
80
81protected:
82 std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_;
83 mecanum_drive_controller::Params params_;
84
92 enum WheelIndex : std::size_t
93 {
94 FRONT_LEFT = 0,
95 FRONT_RIGHT = 1,
96 REAR_RIGHT = 2,
97 REAR_LEFT = 3
98 };
99
103 std::vector<std::string> command_joint_names_;
104
110 std::vector<std::string> state_joint_names_;
111
112 // Names of the references, ex: high level vel commands from MoveIt, Nav2, etc.
113 // used for preceding controller
114 std::vector<std::string> reference_names_;
115
116 // Command subscribers and Controller State, odom state, tf state publishers
117 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
119 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
120
122 rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_;
123 std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_;
124
126 rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_;
127 std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_;
128
130 rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_;
131 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
132
133 // override methods from ChainableControllerInterface
134 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
135
136 bool on_set_chained_mode(bool chained_mode) override;
137
138 Odometry odometry_;
139
140private:
141 // callback for topic interface
142 void reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg);
143
144 double velocity_in_center_frame_linear_x_; // [m/s]
145 double velocity_in_center_frame_linear_y_; // [m/s]
146 double velocity_in_center_frame_angular_z_; // [rad/s]
147};
148
149} // namespace mecanum_drive_controller
150
151#endif // MECANUM_DRIVE_CONTROLLER__MECANUM_DRIVE_CONTROLLER_HPP_
Definition chainable_controller_interface.hpp:37
Definition mecanum_drive_controller.hpp:51
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition mecanum_drive_controller.cpp:57
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:374
WheelIndex
Definition mecanum_drive_controller.hpp:93
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:330
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition mecanum_drive_controller.cpp:257
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition mecanum_drive_controller.cpp:243
std::vector< std::string > command_joint_names_
Definition mecanum_drive_controller.hpp:103
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:294
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition mecanum_drive_controller.cpp:274
std::vector< std::string > state_joint_names_
Definition mecanum_drive_controller.hpp:110
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition odometry.hpp:29
Definition realtime_buffer.hpp:44
Definition realtime_publisher.hpp:54
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:57