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 "controller_interface/chainable_controller_interface.hpp"
30#include "geometry_msgs/msg/twist_stamped.hpp"
31#include "nav_msgs/msg/odometry.hpp"
32#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
33#include "rclcpp_lifecycle/state.hpp"
34#include "realtime_tools/realtime_publisher.hpp"
35#include "realtime_tools/realtime_thread_safe_box.hpp"
36#include "tf2_msgs/msg/tf_message.hpp"
37
38#include "mecanum_drive_controller/mecanum_drive_controller_parameters.hpp"
39#include "mecanum_drive_controller/odometry.hpp"
40namespace mecanum_drive_controller
41{
42// name constants for state interfaces
43static constexpr size_t NR_STATE_ITFS = 4;
44
45// name constants for command interfaces
46static constexpr size_t NR_CMD_ITFS = 4;
47
48// name constants for reference interfaces
49static constexpr size_t NR_REF_ITFS = 3;
50
52{
53public:
55
56 controller_interface::CallbackReturn on_init() override;
57
59
61
62 controller_interface::CallbackReturn on_configure(
63 const rclcpp_lifecycle::State & previous_state) override;
64
65 controller_interface::CallbackReturn on_activate(
66 const rclcpp_lifecycle::State & previous_state) override;
67
68 controller_interface::CallbackReturn on_deactivate(
69 const rclcpp_lifecycle::State & previous_state) override;
70
71 controller_interface::return_type update_reference_from_subscribers(
72 const rclcpp::Time & time, const rclcpp::Duration & period) override;
73
74 controller_interface::return_type update_and_write_commands(
75 const rclcpp::Time & time, const rclcpp::Duration & period) override;
76
77 void set_odometry(
78 const std::shared_ptr<rmw_request_id_t> request_header,
79 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
80 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
81
82 using ControllerReferenceMsg = geometry_msgs::msg::TwistStamped;
83 using OdomStateMsg = nav_msgs::msg::Odometry;
84 using TfStateMsg = tf2_msgs::msg::TFMessage;
85 using ControllerStateMsg = control_msgs::msg::MecanumDriveControllerState;
86
87protected:
88 std::shared_ptr<mecanum_drive_controller::ParamListener> param_listener_;
89 mecanum_drive_controller::Params params_;
90
98 enum WheelIndex : std::size_t
99 {
100 FRONT_LEFT = 0,
101 FRONT_RIGHT = 1,
102 REAR_RIGHT = 2,
103 REAR_LEFT = 3
104 };
105
109 std::vector<std::string> command_joint_names_;
110
116 std::vector<std::string> state_joint_names_;
117
118 // the RT Box containing the command message
120 // save the last reference in case of unable to get value from box
121 ControllerReferenceMsg current_ref_;
122 // the reference timeout value from parameters
123 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0);
124
125 // Command subscribers and Controller State, odom state, tf state publishers
126 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
127
129 rclcpp::Publisher<OdomStateMsg>::SharedPtr odom_s_publisher_;
130 std::unique_ptr<OdomStatePublisher> rt_odom_state_publisher_;
131 OdomStateMsg odom_state_msg_;
132
134 rclcpp::Publisher<TfStateMsg>::SharedPtr tf_odom_s_publisher_;
135 std::unique_ptr<TfStatePublisher> rt_tf_odom_state_publisher_;
136 TfStateMsg tf_odom_state_msg_;
137
139 rclcpp::Publisher<ControllerStateMsg>::SharedPtr controller_s_publisher_;
140 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
141 ControllerStateMsg controller_state_msg_;
142
143 // override methods from ChainableControllerInterface
144 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
145
146 bool on_set_chained_mode(bool chained_mode) override;
147
148 Odometry odometry_;
149 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
150 std::atomic<bool> set_odom_requested_{false};
152 requested_odom_params_;
153
154private:
155 // callback for topic interface
156 void reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg);
157
158 double velocity_in_center_frame_linear_x_; // [m/s]
159 double velocity_in_center_frame_linear_y_; // [m/s]
160 double velocity_in_center_frame_angular_z_; // [rad/s]
161};
162
163} // namespace mecanum_drive_controller
164
165#endif // MECANUM_DRIVE_CONTROLLER__MECANUM_DRIVE_CONTROLLER_HPP_
Definition chainable_controller_interface.hpp:37
Definition mecanum_drive_controller.hpp:52
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition mecanum_drive_controller.cpp:58
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:445
WheelIndex
Definition mecanum_drive_controller.hpp:99
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:392
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition mecanum_drive_controller.cpp:320
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition mecanum_drive_controller.cpp:306
std::vector< std::string > command_joint_names_
Definition mecanum_drive_controller.hpp:109
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:358
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition mecanum_drive_controller.cpp:337
std::vector< std::string > state_joint_names_
Definition mecanum_drive_controller.hpp:116
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:68