ros2_control - iron
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
45// auto-generated by generate_parameter_library
46#include "diff_drive_controller_parameters.hpp"
47
48namespace diff_drive_controller
49{
51{
52 using Twist = geometry_msgs::msg::TwistStamped;
53
54public:
55 DIFF_DRIVE_CONTROLLER_PUBLIC
57
58 DIFF_DRIVE_CONTROLLER_PUBLIC
60
61 DIFF_DRIVE_CONTROLLER_PUBLIC
63
64 DIFF_DRIVE_CONTROLLER_PUBLIC
65 controller_interface::return_type update(
66 const rclcpp::Time & time, const rclcpp::Duration & period) override;
67
68 DIFF_DRIVE_CONTROLLER_PUBLIC
69 controller_interface::CallbackReturn on_init() override;
70
71 DIFF_DRIVE_CONTROLLER_PUBLIC
72 controller_interface::CallbackReturn on_configure(
73 const rclcpp_lifecycle::State & previous_state) override;
74
75 DIFF_DRIVE_CONTROLLER_PUBLIC
76 controller_interface::CallbackReturn on_activate(
77 const rclcpp_lifecycle::State & previous_state) override;
78
79 DIFF_DRIVE_CONTROLLER_PUBLIC
80 controller_interface::CallbackReturn on_deactivate(
81 const rclcpp_lifecycle::State & previous_state) override;
82
83 DIFF_DRIVE_CONTROLLER_PUBLIC
84 controller_interface::CallbackReturn on_cleanup(
85 const rclcpp_lifecycle::State & previous_state) override;
86
87 DIFF_DRIVE_CONTROLLER_PUBLIC
88 controller_interface::CallbackReturn on_error(
89 const rclcpp_lifecycle::State & previous_state) override;
90
91 DIFF_DRIVE_CONTROLLER_PUBLIC
92 controller_interface::CallbackReturn on_shutdown(
93 const rclcpp_lifecycle::State & previous_state) override;
94
95protected:
97 {
98 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
99 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
100 };
101
102 const char * feedback_type() const;
103 controller_interface::CallbackReturn configure_side(
104 const std::string & side, const std::vector<std::string> & wheel_names,
105 std::vector<WheelHandle> & registered_handles);
106
107 std::vector<WheelHandle> registered_left_wheel_handles_;
108 std::vector<WheelHandle> registered_right_wheel_handles_;
109
110 // Parameters from ROS for diff_drive_controller
111 std::shared_ptr<ParamListener> param_listener_;
112 Params params_;
113 /* Number of wheels on each side of the robot. This is important to take the wheels slip into
114 * account when multiple wheels on each side are present. If there are more wheels then control
115 * signals for each side, you should enter number for control signals. For example, Husky has two
116 * wheels on each side, but they use one control signal, in this case '1' is the correct value of
117 * the parameter. */
118 int wheels_per_side_;
119
120 Odometry odometry_;
121
122 // Timeout to consider cmd_vel commands old
123 std::chrono::milliseconds cmd_vel_timeout_{500};
124
125 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
126 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
127 realtime_odometry_publisher_ = nullptr;
128
129 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
130 nullptr;
131 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
132 realtime_odometry_transform_publisher_ = nullptr;
133
134 bool subscriber_is_active_ = false;
135 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
136 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
137 velocity_command_unstamped_subscriber_ = nullptr;
138
139 realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_{nullptr};
140
141 std::queue<Twist> previous_commands_; // last two commands
142
143 // speed limiters
144 SpeedLimiter limiter_linear_;
145 SpeedLimiter limiter_angular_;
146
147 bool publish_limited_velocity_ = false;
148 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr;
149 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
150 nullptr;
151
152 rclcpp::Time previous_update_timestamp_{0};
153
154 // publish rate limiter
155 double publish_rate_ = 50.0;
156 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
157 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
158
159 bool is_halted = false;
160 bool use_stamped_vel_ = true;
161
162 bool reset();
163 void halt();
164};
165} // namespace diff_drive_controller
166#endif // DIFF_DRIVE_CONTROLLER__DIFF_DRIVE_CONTROLLER_HPP_
Definition controller_interface.hpp:29
Definition diff_drive_controller.hpp:51
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition diff_drive_controller.cpp:101
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition diff_drive_controller.cpp:87
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition diff_drive_controller.cpp:56
DIFF_DRIVE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition diff_drive_controller.cpp:73
Definition odometry.hpp:33
Definition realtime_box.hpp:60
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56
Definition diff_drive_controller.hpp:97