ros2_control - humble
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.hpp"
41#include "realtime_tools/realtime_publisher.hpp"
42#include "tf2_msgs/msg/tf_message.hpp"
43
44#include "diff_drive_controller_parameters.hpp"
45
46namespace diff_drive_controller
47{
49{
50 using Twist = geometry_msgs::msg::TwistStamped;
51
52public:
53 DIFF_DRIVE_CONTROLLER_PUBLIC
55
56 DIFF_DRIVE_CONTROLLER_PUBLIC
58
59 DIFF_DRIVE_CONTROLLER_PUBLIC
61
62 DIFF_DRIVE_CONTROLLER_PUBLIC
63 controller_interface::return_type update(
64 const rclcpp::Time & time, const rclcpp::Duration & period) override;
65
66 DIFF_DRIVE_CONTROLLER_PUBLIC
67 controller_interface::CallbackReturn on_init() override;
68
69 DIFF_DRIVE_CONTROLLER_PUBLIC
70 controller_interface::CallbackReturn on_configure(
71 const rclcpp_lifecycle::State & previous_state) override;
72
73 DIFF_DRIVE_CONTROLLER_PUBLIC
74 controller_interface::CallbackReturn on_activate(
75 const rclcpp_lifecycle::State & previous_state) override;
76
77 DIFF_DRIVE_CONTROLLER_PUBLIC
78 controller_interface::CallbackReturn on_deactivate(
79 const rclcpp_lifecycle::State & previous_state) override;
80
81 DIFF_DRIVE_CONTROLLER_PUBLIC
82 controller_interface::CallbackReturn on_cleanup(
83 const rclcpp_lifecycle::State & previous_state) override;
84
85 DIFF_DRIVE_CONTROLLER_PUBLIC
86 controller_interface::CallbackReturn on_error(
87 const rclcpp_lifecycle::State & previous_state) override;
88
89 DIFF_DRIVE_CONTROLLER_PUBLIC
90 controller_interface::CallbackReturn on_shutdown(
91 const rclcpp_lifecycle::State & previous_state) override;
92
93protected:
95 {
96 std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback;
97 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
98 };
99
100 const char * feedback_type() const;
101 controller_interface::CallbackReturn configure_side(
102 const std::string & side, const std::vector<std::string> & wheel_names,
103 std::vector<WheelHandle> & registered_handles);
104
105 std::vector<WheelHandle> registered_left_wheel_handles_;
106 std::vector<WheelHandle> registered_right_wheel_handles_;
107
108 // Parameters from ROS for diff_drive_controller
109 std::shared_ptr<ParamListener> param_listener_;
110 Params params_;
111
112 Odometry odometry_;
113
114 // Timeout to consider cmd_vel commands old
115 std::chrono::milliseconds cmd_vel_timeout_{500};
116
117 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
118 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
119 realtime_odometry_publisher_ = nullptr;
120
121 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
122 nullptr;
123 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
124 realtime_odometry_transform_publisher_ = nullptr;
125
126 bool subscriber_is_active_ = false;
127 rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
128 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
129 velocity_command_unstamped_subscriber_ = nullptr;
130
131 realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_{nullptr};
132
133 std::queue<Twist> previous_commands_; // last two commands
134
135 // speed limiters
136 SpeedLimiter limiter_linear_;
137 SpeedLimiter limiter_angular_;
138
139 bool publish_limited_velocity_ = false;
140 std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr;
141 std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
142 nullptr;
143
144 rclcpp::Time previous_update_timestamp_{0};
145
146 // publish rate limiter
147 double publish_rate_ = 50.0;
148 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
149 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
150
151 bool is_halted = false;
152 bool use_stamped_vel_ = true;
153
154 bool reset();
155 void halt();
156};
157} // namespace diff_drive_controller
158#endif // DIFF_DRIVE_CONTROLLER__DIFF_DRIVE_CONTROLLER_HPP_
Definition controller_interface.hpp:29
Definition diff_drive_controller.hpp:49
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:95