ros2_control - rolling
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 <atomic>
23#include <chrono>
24#include <memory>
25#include <queue>
26#include <string>
27#include <vector>
28
29#include "control_msgs/srv/set_odometry.hpp"
30#include "controller_interface/chainable_controller_interface.hpp"
31#include "diff_drive_controller/odometry.hpp"
32#include "diff_drive_controller/speed_limiter.hpp"
33#include "geometry_msgs/msg/twist_stamped.hpp"
34#include "nav_msgs/msg/odometry.hpp"
35#include "odometry.hpp"
36#include "rclcpp_lifecycle/state.hpp"
37#include "realtime_tools/realtime_publisher.hpp"
38#include "realtime_tools/realtime_thread_safe_box.hpp"
39#include "tf2_msgs/msg/tf_message.hpp"
40
41// auto-generated by generate_parameter_library
42#include "diff_drive_controller/diff_drive_controller_parameters.hpp"
43
44namespace diff_drive_controller
45{
47{
48 using TwistStamped = geometry_msgs::msg::TwistStamped;
49
50public:
52
54
56
57 // Chainable controller replaces update() with the following two functions
58 controller_interface::return_type update_reference_from_subscribers(
59 const rclcpp::Time & time, const rclcpp::Duration & period) override;
60
61 controller_interface::return_type update_and_write_commands(
62 const rclcpp::Time & time, const rclcpp::Duration & period) override;
63
64 controller_interface::CallbackReturn on_init() override;
65
66 controller_interface::CallbackReturn on_configure(
67 const rclcpp_lifecycle::State & previous_state) override;
68
69 controller_interface::CallbackReturn on_activate(
70 const rclcpp_lifecycle::State & previous_state) override;
71
72 controller_interface::CallbackReturn on_deactivate(
73 const rclcpp_lifecycle::State & previous_state) override;
74
75 controller_interface::CallbackReturn on_cleanup(
76 const rclcpp_lifecycle::State & previous_state) override;
77
78 controller_interface::CallbackReturn on_error(
79 const rclcpp_lifecycle::State & previous_state) override;
80
81 void set_odometry(
82 const std::shared_ptr<rmw_request_id_t> request_header,
83 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
84 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
85
86protected:
87 bool on_set_chained_mode(bool chained_mode) override;
88
89 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
90
92 {
93 std::optional<std::reference_wrapper<const hardware_interface::LoanedStateInterface>> feedback;
94 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity;
95 };
96
97 const char * feedback_type() const;
98 controller_interface::CallbackReturn configure_side(
99 const std::string & side, const std::vector<std::string> & wheel_names,
100 std::vector<WheelHandle> & registered_handles);
101
102 std::vector<WheelHandle> registered_left_wheel_handles_;
103 std::vector<WheelHandle> registered_right_wheel_handles_;
104
105 // Parameters from ROS for diff_drive_controller
106 std::shared_ptr<ParamListener> param_listener_;
107 Params params_;
108 /* Number of wheels on each side of the robot. This is important to take the wheels slip into
109 * account when multiple wheels on each side are present. If there are more wheels then control
110 * signals for each side, you should enter number for control signals. For example, Husky has two
111 * wheels on each side, but they use one control signal, in this case '1' is the correct value of
112 * the parameter. */
113 int wheels_per_side_;
114
115 Odometry odometry_;
116
117 // Timeout to consider cmd_vel commands old
118 rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5);
119
120 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
121 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
122 realtime_odometry_publisher_ = nullptr;
123 nav_msgs::msg::Odometry odometry_message_;
124
125 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
126 nullptr;
127 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
128 realtime_odometry_transform_publisher_ = nullptr;
129 tf2_msgs::msg::TFMessage odometry_transform_message_;
130
131 bool subscriber_is_active_ = false;
132 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
133
134 // the realtime container to exchange the reference from subscriber
136 // save the last reference in case of unable to get value from box
137 TwistStamped command_msg_;
138
139 std::queue<std::array<double, 2>> previous_two_commands_;
140 // speed limiters
141 std::unique_ptr<SpeedLimiter> limiter_linear_;
142 std::unique_ptr<SpeedLimiter> limiter_angular_;
143
144 bool publish_limited_velocity_ = false;
145 std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ = nullptr;
146 std::shared_ptr<realtime_tools::RealtimePublisher<TwistStamped>>
147 realtime_limited_velocity_publisher_ = nullptr;
148 TwistStamped limited_velocity_message_;
149
150 rclcpp::Time previous_update_timestamp_{0};
151
152 // publish rate limiter
153 double publish_rate_ = 50.0;
154 rclcpp::Duration publish_period_ = rclcpp::Duration::from_nanoseconds(0);
155 rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED};
156
157 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
158 std::atomic<bool> set_odom_requested_{false};
160 requested_odom_params_;
161
162 bool reset();
163 void halt();
164
165private:
166 void reset_buffers();
167};
168} // namespace diff_drive_controller
169#endif // DIFF_DRIVE_CONTROLLER__DIFF_DRIVE_CONTROLLER_HPP_
Definition chainable_controller_interface.hpp:37
Definition diff_drive_controller.hpp:47
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 diff_drive_controller.cpp:108
bool on_set_chained_mode(bool chained_mode) override
Virtual method that each chainable controller should implement to switch chained mode.
Definition diff_drive_controller.cpp:720
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 diff_drive_controller.cpp:145
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition diff_drive_controller.cpp:89
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition diff_drive_controller.cpp:58
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition diff_drive_controller.cpp:723
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition diff_drive_controller.cpp:75
Definition odometry.hpp:36
Definition realtime_thread_safe_box.hpp:68
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:68
Definition diff_drive_controller.hpp:92