ros2_control - humble
Loading...
Searching...
No Matches
steering_controllers_library.hpp
1// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
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#ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_CONTROLLERS_LIBRARY_HPP_
16#define STEERING_CONTROLLERS_LIBRARY__STEERING_CONTROLLERS_LIBRARY_HPP_
17
18#include <chrono>
19#include <cmath>
20#include <memory>
21#include <queue>
22#include <string>
23#include <utility>
24#include <vector>
25
26#include "controller_interface/chainable_controller_interface.hpp"
27#include "hardware_interface/handle.hpp"
28#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
29#include "rclcpp_lifecycle/state.hpp"
30#include "realtime_tools/realtime_buffer.hpp"
31#include "realtime_tools/realtime_publisher.hpp"
32#include "std_srvs/srv/set_bool.hpp"
33#include "steering_controllers_library/steering_odometry.hpp"
34#include "steering_controllers_library/visibility_control.h"
35#include "steering_controllers_library_parameters.hpp"
36
37// TODO(anyone): Replace with controller specific messages
38#include "ackermann_msgs/msg/ackermann_drive_stamped.hpp"
39#include "control_msgs/msg/steering_controller_status.hpp"
40#include "geometry_msgs/msg/twist.hpp"
41#include "geometry_msgs/msg/twist_stamped.hpp"
42#include "nav_msgs/msg/odometry.hpp"
43#include "tf2_msgs/msg/tf_message.hpp"
44
45namespace steering_controllers_library
46{
48{
49public:
50 STEERING_CONTROLLERS__VISIBILITY_PUBLIC SteeringControllersLibrary();
51
52 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC void
53 initialize_implementation_parameter_listener() = 0;
54
55 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init() override;
56
57 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration
58 command_interface_configuration() const override;
59
60 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration
61 state_interface_configuration() const override;
62
63 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn
64 configure_odometry() = 0;
65
66 virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC bool update_odometry(
67 const rclcpp::Duration & period) = 0;
68
69 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure(
70 const rclcpp_lifecycle::State & previous_state) override;
71
72 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate(
73 const rclcpp_lifecycle::State & previous_state) override;
74
75 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate(
76 const rclcpp_lifecycle::State & previous_state) override;
77
78 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
80
81 STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
82 update_and_write_commands(const rclcpp::Time & time, const rclcpp::Duration & period) override;
83
84 using ControllerAckermannReferenceMsg = ackermann_msgs::msg::AckermannDriveStamped;
85 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
86 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
87 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
88 using AckermannControllerState = control_msgs::msg::SteeringControllerStatus;
89
90protected:
91 controller_interface::CallbackReturn set_interface_numbers(
92 size_t nr_state_itfs, size_t nr_cmd_itfs, size_t nr_ref_itfs);
93
94 std::shared_ptr<steering_controllers_library::ParamListener> param_listener_;
95 steering_controllers_library::Params params_;
96
97 // Command subscribers and Controller State publisher
98 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ = nullptr;
99 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_ackermann_ = nullptr;
100 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr ref_subscriber_unstamped_ = nullptr;
102 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0); // 0ms
103
106
107 rclcpp::Publisher<ControllerStateMsgOdom>::SharedPtr odom_s_publisher_;
108 rclcpp::Publisher<ControllerStateMsgTf>::SharedPtr tf_odom_s_publisher_;
109
110 std::unique_ptr<ControllerStatePublisherOdom> rt_odom_state_publisher_;
111 std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_;
112
113 // override methods from ChainableControllerInterface
114 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
115
116 bool on_set_chained_mode(bool chained_mode) override;
117
120
121 AckermannControllerState published_state_;
122
124 rclcpp::Publisher<AckermannControllerState>::SharedPtr controller_s_publisher_;
125 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
126
127 // name constants for state interfaces
128 size_t nr_state_itfs_;
129 // name constants for command interfaces
130 size_t nr_cmd_itfs_;
131 // name constants for reference interfaces
132 size_t nr_ref_itfs_;
133
134 // last velocity commands for open loop odometry
135 double last_linear_velocity_ = 0.0;
136 double last_angular_velocity_ = 0.0;
137
138 std::vector<std::string> rear_wheels_state_names_;
139 std::vector<std::string> front_wheels_state_names_;
140
141private:
142 // callback for topic interface
143 STEERING_CONTROLLERS__VISIBILITY_LOCAL void reference_callback(
144 const std::shared_ptr<ControllerTwistReferenceMsg> msg);
145 void reference_callback_unstamped(const std::shared_ptr<geometry_msgs::msg::Twist> msg);
146};
147
148} // namespace steering_controllers_library
149
150#endif // STEERING_CONTROLLERS_LIBRARY__STEERING_CONTROLLERS_LIBRARY_HPP_
Definition chainable_controller_interface.hpp:35
Definition realtime_buffer.hpp:44
Definition realtime_publisher.hpp:54
Definition steering_controllers_library.hpp:48
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type update_reference_from_subscribers() override
Update reference from input topics when not in chained mode.
Definition steering_controllers_library.cpp:405
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition steering_controllers_library.cpp:282
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition steering_controllers_library.cpp:362
bool on_set_chained_mode(bool chained_mode) override
Virtual method that each chainable controller should implement to switch chained mode.
Definition steering_controllers_library.cpp:380
STEERING_CONTROLLERS__VISIBILITY_PUBLIC 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 steering_controllers_library.cpp:413
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition steering_controllers_library.cpp:59
steering_odometry::SteeringOdometry odometry_
Odometry:
Definition steering_controllers_library.hpp:119
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition steering_controllers_library.cpp:320
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition steering_odometry.hpp:41
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56