ros2_control - rolling
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 <cmath>
19#include <memory>
20#include <string>
21#include <vector>
22
23#include "controller_interface/chainable_controller_interface.hpp"
24#include "hardware_interface/handle.hpp"
25#include "rclcpp_lifecycle/state.hpp"
26#include "realtime_tools/realtime_publisher.hpp"
27#include "realtime_tools/realtime_thread_safe_box.hpp"
28
29// TODO(anyone): Replace with controller specific messages
30#include "control_msgs/msg/steering_controller_status.hpp"
31#include "control_msgs/srv/set_odometry.hpp"
32#include "geometry_msgs/msg/twist_stamped.hpp"
33#include "nav_msgs/msg/odometry.hpp"
34#include "tf2_msgs/msg/tf_message.hpp"
35
36#include "steering_controllers_library/steering_controllers_library_parameters.hpp"
37#include "steering_controllers_library/steering_kinematics.hpp"
38
39namespace steering_controllers_library
40{
42{
43public:
45
46 virtual void initialize_implementation_parameter_listener() = 0;
47
48 controller_interface::CallbackReturn on_init() override;
49
51
53
54 virtual controller_interface::CallbackReturn configure_odometry() = 0;
55
56 virtual bool update_odometry(const rclcpp::Duration & period) = 0;
57
58 void set_odometry(
59 const std::shared_ptr<rmw_request_id_t> request_header,
60 const std::shared_ptr<control_msgs::srv::SetOdometry::Request> req,
61 std::shared_ptr<control_msgs::srv::SetOdometry::Response> res);
62
63 bool reset();
64
65 controller_interface::CallbackReturn on_configure(
66 const rclcpp_lifecycle::State & previous_state) override;
67
68 controller_interface::CallbackReturn on_activate(
69 const rclcpp_lifecycle::State & previous_state) override;
70
71 controller_interface::CallbackReturn on_deactivate(
72 const rclcpp_lifecycle::State & previous_state) override;
73
74 controller_interface::CallbackReturn on_cleanup(
75 const rclcpp_lifecycle::State & previous_state) override;
76
77 controller_interface::CallbackReturn on_error(
78 const rclcpp_lifecycle::State & previous_state) override;
79
80 controller_interface::return_type update_reference_from_subscribers(
81 const rclcpp::Time & time, const rclcpp::Duration & period) override;
82
83 controller_interface::return_type update_and_write_commands(
84 const rclcpp::Time & time, const rclcpp::Duration & period) override;
85
86 using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
87 using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
88 using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
89 using SteeringControllerStateMsg = control_msgs::msg::SteeringControllerStatus;
90
91protected:
92 controller_interface::CallbackReturn set_interface_numbers(
93 size_t nr_state_itfs, size_t nr_cmd_itfs, size_t nr_ref_itfs);
94
95 std::shared_ptr<steering_controllers_library::ParamListener> param_listener_;
96 steering_controllers_library::Params params_;
97
98 // the RT Box containing the command message
100 // save the last reference in case of unable to get value from box
101 ControllerTwistReferenceMsg current_ref_;
102 rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0); // 0ms
103
104 // Command subscribers and Controller State publisher
105 rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ = nullptr;
108
109 rclcpp::Publisher<ControllerStateMsgOdom>::SharedPtr odom_s_publisher_;
110 rclcpp::Publisher<ControllerStateMsgTf>::SharedPtr tf_odom_s_publisher_;
111
112 std::unique_ptr<ControllerStatePublisherOdom> rt_odom_state_publisher_;
113 ControllerStateMsgOdom odom_state_msg_;
114 std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_;
115 ControllerStateMsgTf tf_odom_state_msg_;
116
117 // override methods from ChainableControllerInterface
118 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
119
120 bool on_set_chained_mode(bool chained_mode) override;
121
124 rclcpp::Service<control_msgs::srv::SetOdometry>::SharedPtr set_odom_service_;
125 std::atomic<bool> set_odom_requested_{false};
127 requested_odom_params_;
128
129 SteeringControllerStateMsg published_state_;
130
132 rclcpp::Publisher<SteeringControllerStateMsg>::SharedPtr controller_s_publisher_;
133 std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;
134 SteeringControllerStateMsg controller_state_msg_;
135
136 // name constants for state interfaces
137 size_t nr_state_itfs_;
138 // name constants for command interfaces
139 size_t nr_cmd_itfs_;
140 // name constants for reference interfaces
141 size_t nr_ref_itfs_;
142
143 // last velocity commands for open loop odometry
144 double last_linear_velocity_ = 0.0;
145 double last_angular_velocity_ = 0.0;
146
147 std::vector<std::string> traction_joints_state_names_;
148 std::vector<std::string> steering_joints_state_names_;
149
150private:
151 // callback for topic interface
152 void reference_callback(const std::shared_ptr<ControllerTwistReferenceMsg> msg);
153};
154
155} // namespace steering_controllers_library
156
157#endif // STEERING_CONTROLLERS_LIBRARY__STEERING_CONTROLLERS_LIBRARY_HPP_
Definition chainable_controller_interface.hpp:37
Definition realtime_publisher.hpp:55
Definition realtime_thread_safe_box.hpp:68
Definition steering_controllers_library.hpp:42
steering_kinematics::SteeringKinematics odometry_
Odometry:
Definition steering_controllers_library.hpp:123
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition steering_controllers_library.cpp:400
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition steering_controllers_library.cpp:446
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:466
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:561
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition steering_controllers_library.cpp:55
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 steering_controllers_library.cpp:516
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition steering_controllers_library.cpp:420
The SteeringKinematics class handles forward kinematics (odometry calculations) and inverse kinematic...
Definition steering_kinematics.hpp:47
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:69