ros2_control - foxy
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::return_type init(const std::string & controller_name) override;
59
60 DIFF_DRIVE_CONTROLLER_PUBLIC
61 controller_interface::InterfaceConfiguration command_interface_configuration() const override;
62
63 DIFF_DRIVE_CONTROLLER_PUBLIC
64 controller_interface::InterfaceConfiguration state_interface_configuration() const override;
65
66 DIFF_DRIVE_CONTROLLER_PUBLIC
67 controller_interface::return_type update() override;
68
69 DIFF_DRIVE_CONTROLLER_PUBLIC
70 CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;
71
72 DIFF_DRIVE_CONTROLLER_PUBLIC
73 CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
74
75 DIFF_DRIVE_CONTROLLER_PUBLIC
76 CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
77
78 DIFF_DRIVE_CONTROLLER_PUBLIC
79 CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;
80
81 DIFF_DRIVE_CONTROLLER_PUBLIC
82 CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
83
84 DIFF_DRIVE_CONTROLLER_PUBLIC
85 CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
86
87protected:
89 {
90 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position;
91 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
92 };
93
94 CallbackReturn configure_side(
95 const std::string & side, const std::vector<std::string> & wheel_names,
96 std::vector<WheelHandle> & registered_handles);
97
98 std::vector<std::string> left_wheel_names_;
99 std::vector<std::string> right_wheel_names_;
100
101 std::vector<WheelHandle> registered_left_wheel_handles_;
102 std::vector<WheelHandle> registered_right_wheel_handles_;
103
105 {
106 size_t wheels_per_side = 0;
107 double separation = 0.0; // w.r.t. the midpoint of the wheel width
108 double radius = 0.0; // Assumed to be the same for both wheels
109 double separation_multiplier = 1.0;
110 double left_radius_multiplier = 1.0;
111 double right_radius_multiplier = 1.0;
112 } wheel_params_;
113
115 {
116 bool open_loop = false;
117 bool enable_odom_tf = true;
118 std::string base_frame_id = "base_link";
119 std::string odom_frame_id = "odom";
120 std::array<double, 6> pose_covariance_diagonal;
121 std::array<double, 6> twist_covariance_diagonal;
122 } odom_params_;
123
124 Odometry odometry_;
125
126 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
127 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
128 realtime_odometry_publisher_ = nullptr;
129
130 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
131 nullptr;
132 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
133 realtime_odometry_transform_publisher_ = nullptr;
134
135 // Timeout to consider cmd_vel commands old
136 std::chrono::milliseconds cmd_vel_timeout_{500};
137
138 bool subscriber_is_active_ = false;
139 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
140 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
141 velocity_command_unstamped_subscriber_ = nullptr;
142
143 realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_{nullptr};
144
145 std::queue<Twist> previous_commands_; // last two commands
146
147 // speed limiters
148 SpeedLimiter limiter_linear_;
149 SpeedLimiter limiter_angular_;
150
151 bool publish_limited_velocity_ = false;
152 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr;
153 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
154 nullptr;
155
156 rclcpp::Time previous_update_timestamp_{0};
157
158 // publish rate limiter
159 double publish_rate_ = 50.0;
160 rclcpp::Duration publish_period_{0, 0};
161 rclcpp::Time previous_publish_timestamp_{0};
162
163 bool is_halted = false;
164 bool use_stamped_vel_ = true;
165
166 bool reset();
167 void halt();
168};
169} // namespace diff_drive_controller
170#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.h:48
Configuring what command/state interfaces to claim.
Definition controller_interface.hpp:63
Definition diff_drive_controller.hpp:115
Definition diff_drive_controller.hpp:89
Definition diff_drive_controller.hpp:105