ros2_control - galactic
Loading...
Searching...
No Matches
diff_drive_controller.hpp
1// Copyright 2020 PAL Robotics S.L.
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/*
16 * Author: Bence Magyar, Enrique Fernández, Manuel Meraz
17 */
18
19#ifndef DIFF_DRIVE_CONTROLLER__DIFF_DRIVE_CONTROLLER_HPP_
20#define DIFF_DRIVE_CONTROLLER__DIFF_DRIVE_CONTROLLER_HPP_
21
22#include <chrono>
23#include <cmath>
24#include <memory>
25#include <queue>
26#include <string>
27#include <vector>
28
29#include "controller_interface/controller_interface.hpp"
30#include "diff_drive_controller/odometry.hpp"
31#include "diff_drive_controller/speed_limiter.hpp"
32#include "diff_drive_controller/visibility_control.h"
33#include "geometry_msgs/msg/twist.hpp"
34#include "geometry_msgs/msg/twist_stamped.hpp"
35#include "hardware_interface/handle.hpp"
36#include "nav_msgs/msg/odometry.hpp"
37#include "odometry.hpp"
38#include "rclcpp/rclcpp.hpp"
39#include "rclcpp_lifecycle/state.hpp"
40#include "realtime_tools/realtime_box.h"
41#include "realtime_tools/realtime_buffer.h"
42#include "realtime_tools/realtime_publisher.h"
43#include "tf2_msgs/msg/tf_message.hpp"
44
45namespace diff_drive_controller
46{
47using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
48
50{
51 using Twist = geometry_msgs::msg::TwistStamped;
52
53public:
54 DIFF_DRIVE_CONTROLLER_PUBLIC
56
57 DIFF_DRIVE_CONTROLLER_PUBLIC
58 controller_interface::InterfaceConfiguration command_interface_configuration() const override;
59
60 DIFF_DRIVE_CONTROLLER_PUBLIC
61 controller_interface::InterfaceConfiguration state_interface_configuration() const override;
62
63 DIFF_DRIVE_CONTROLLER_PUBLIC
64 controller_interface::return_type update(
65 const rclcpp::Time & time, const rclcpp::Duration & period) override;
66
67 DIFF_DRIVE_CONTROLLER_PUBLIC
68 CallbackReturn on_init() override;
69
70 DIFF_DRIVE_CONTROLLER_PUBLIC
71 CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;
72
73 DIFF_DRIVE_CONTROLLER_PUBLIC
74 CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
75
76 DIFF_DRIVE_CONTROLLER_PUBLIC
77 CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
78
79 DIFF_DRIVE_CONTROLLER_PUBLIC
80 CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;
81
82 DIFF_DRIVE_CONTROLLER_PUBLIC
83 CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
84
85 DIFF_DRIVE_CONTROLLER_PUBLIC
86 CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
87
88protected:
90 {
91 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
92 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
93 };
94
95 const char * feedback_type() const;
96 CallbackReturn configure_side(
97 const std::string & side, const std::vector<std::string> & wheel_names,
98 std::vector<WheelHandle> & registered_handles);
99
100 std::vector<std::string> left_wheel_names_;
101 std::vector<std::string> right_wheel_names_;
102
103 std::vector<WheelHandle> registered_left_wheel_handles_;
104 std::vector<WheelHandle> registered_right_wheel_handles_;
105
107 {
108 size_t wheels_per_side = 0;
109 double separation = 0.0; // w.r.t. the midpoint of the wheel width
110 double radius = 0.0; // Assumed to be the same for both wheels
111 double separation_multiplier = 1.0;
112 double left_radius_multiplier = 1.0;
113 double right_radius_multiplier = 1.0;
114 } wheel_params_;
115
117 {
118 bool open_loop = false;
119 bool position_feedback = true;
120 bool enable_odom_tf = true;
121 std::string base_frame_id = "base_link";
122 std::string odom_frame_id = "odom";
123 std::array<double, 6> pose_covariance_diagonal;
124 std::array<double, 6> twist_covariance_diagonal;
125 } odom_params_;
126
127 Odometry odometry_;
128
129 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
130 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
131 realtime_odometry_publisher_ = nullptr;
132
133 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
134 nullptr;
135 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
136 realtime_odometry_transform_publisher_ = nullptr;
137
138 // Timeout to consider cmd_vel commands old
139 std::chrono::milliseconds cmd_vel_timeout_{500};
140
141 bool subscriber_is_active_ = false;
142 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
143 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
144 velocity_command_unstamped_subscriber_ = nullptr;
145
146 realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_{nullptr};
147
148 std::queue<Twist> previous_commands_; // last two commands
149
150 // speed limiters
151 SpeedLimiter limiter_linear_;
152 SpeedLimiter limiter_angular_;
153
154 bool publish_limited_velocity_ = false;
155 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr;
156 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
157 nullptr;
158
159 rclcpp::Time previous_update_timestamp_{0};
160
161 // publish rate limiter
162 double publish_rate_ = 50.0;
163 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
164 rclcpp::Time previous_publish_timestamp_{0};
165
166 bool is_halted = false;
167 bool use_stamped_vel_ = true;
168
169 bool reset();
170 void halt();
171};
172} // namespace diff_drive_controller
173#endif // DIFF_DRIVE_CONTROLLER__DIFF_DRIVE_CONTROLLER_HPP_
Definition controller_interface.hpp:69
Definition diff_drive_controller.hpp:50
Definition odometry.hpp:33
Definition realtime_box.hpp:47
Configuring what command/state interfaces to claim.
Definition controller_interface.hpp:63
Definition diff_drive_controller.hpp:117
Definition diff_drive_controller.hpp:90
Definition diff_drive_controller.hpp:107