ros2_control - foxy
Loading...
Searching...
No Matches
tricycle_controller.hpp
1// Copyright 2022 Pixel Robotics.
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: Tony Najjar, Borong Yuan
17 */
18
19#ifndef TRICYCLE_CONTROLLER__TRICYCLE_CONTROLLER_HPP_
20#define TRICYCLE_CONTROLLER__TRICYCLE_CONTROLLER_HPP_
21
22#include <chrono>
23#include <cmath>
24#include <memory>
25#include <queue>
26#include <string>
27#include <vector>
28
29#include "ackermann_msgs/msg/ackermann_drive.hpp"
30#include "controller_interface/controller_interface.hpp"
31#include "geometry_msgs/msg/twist.hpp"
32#include "geometry_msgs/msg/twist_stamped.hpp"
33#include "hardware_interface/handle.hpp"
34#include "nav_msgs/msg/odometry.hpp"
35#include "rclcpp/rclcpp.hpp"
36#include "rclcpp_lifecycle/state.hpp"
37#include "realtime_tools/realtime_box.h"
38#include "realtime_tools/realtime_buffer.h"
39#include "realtime_tools/realtime_publisher.h"
40#include "std_srvs/srv/empty.hpp"
41#include "tf2_msgs/msg/tf_message.hpp"
42#include "tricycle_controller/odometry.hpp"
43#include "tricycle_controller/steering_limiter.hpp"
44#include "tricycle_controller/traction_limiter.hpp"
45#include "tricycle_controller/visibility_control.h"
46
47namespace tricycle_controller
48{
49using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
50
52{
53 using Twist = geometry_msgs::msg::Twist;
54 using TwistStamped = geometry_msgs::msg::TwistStamped;
55 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
56
57public:
58 TRICYCLE_CONTROLLER_PUBLIC
60
61 TRICYCLE_CONTROLLER_PUBLIC
62 controller_interface::InterfaceConfiguration command_interface_configuration() const override;
63
64 TRICYCLE_CONTROLLER_PUBLIC
65 controller_interface::InterfaceConfiguration state_interface_configuration() const override;
66
67 TRICYCLE_CONTROLLER_PUBLIC
68 controller_interface::return_type update() override;
69
70 TRICYCLE_CONTROLLER_PUBLIC
71 controller_interface::return_type init(const std::string & controller_name) override;
72
73 TRICYCLE_CONTROLLER_PUBLIC
74 CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;
75
76 TRICYCLE_CONTROLLER_PUBLIC
77 CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
78
79 TRICYCLE_CONTROLLER_PUBLIC
80 CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
81
82 TRICYCLE_CONTROLLER_PUBLIC
83 CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;
84
85 TRICYCLE_CONTROLLER_PUBLIC
86 CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
87
88 TRICYCLE_CONTROLLER_PUBLIC
89 CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
90
91protected:
93 {
94 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
95 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
96 };
98 {
99 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
100 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
101 };
102
103 CallbackReturn get_traction(
104 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
105 CallbackReturn get_steering(
106 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
107 double convert_trans_rot_vel_to_steering_angle(double v, double omega, double wheelbase);
108 std::tuple<double, double> twist_to_ackermann(double linear_command, double angular_command);
109
110 std::string traction_joint_name_;
111 std::string steering_joint_name_;
112
113 // HACK: put into vector to avoid initializing structs because they have no default constructors
114 std::vector<TractionHandle> traction_joint_;
115 std::vector<SteeringHandle> steering_joint_;
116
118 {
119 double wheelbase = 0.0;
120 double radius = 0.0;
121 } wheel_params_;
122
124 {
125 bool open_loop = false;
126 bool enable_odom_tf = false;
127 bool odom_only_twist = false; // for doing the pose integration in separate node
128 std::string base_frame_id = "base_link";
129 std::string odom_frame_id = "odom";
130 std::array<double, 6> pose_covariance_diagonal;
131 std::array<double, 6> twist_covariance_diagonal;
132 } odom_params_;
133
134 bool publish_ackermann_command_ = false;
135 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ = nullptr;
136 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
137 realtime_ackermann_command_publisher_ = nullptr;
138
139 Odometry odometry_;
140
141 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
142 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
143 realtime_odometry_publisher_ = nullptr;
144
145 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
146 nullptr;
147 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
148 realtime_odometry_transform_publisher_ = nullptr;
149
150 // Timeout to consider cmd_vel commands old
151 std::chrono::milliseconds cmd_vel_timeout_{500};
152
153 bool subscriber_is_active_ = false;
154 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
155 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
156 velocity_command_unstamped_subscriber_ = nullptr;
157
158 realtime_tools::RealtimeBox<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr};
159
160 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
161
162 std::queue<AckermannDrive> previous_commands_; // last two commands
163
164 // speed limiters
165 TractionLimiter limiter_traction_;
166 SteeringLimiter limiter_steering_;
167
168 rclcpp::Time previous_update_timestamp_{0};
169
170 // publish rate limiter
171 double publish_rate_ = 50.0;
172 rclcpp::Duration publish_period_{0, 0};
173 rclcpp::Time previous_publish_timestamp_{0};
174
175 bool is_halted = false;
176 bool use_stamped_vel_ = true;
177
178 void reset_odometry(
179 const std::shared_ptr<rmw_request_id_t> request_header,
180 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
181 std::shared_ptr<std_srvs::srv::Empty::Response> res);
182 bool reset();
183 void halt();
184};
185} // namespace tricycle_controller
186#endif // TRICYCLE_CONTROLLER__TRICYCLE_CONTROLLER_HPP_
Definition controller_interface.hpp:69
Definition realtime_box.h:48
Definition odometry.hpp:30
Definition tricycle_controller.hpp:52
Configuring what command/state interfaces to claim.
Definition controller_interface.hpp:63
Definition tricycle_controller.hpp:124
Definition tricycle_controller.hpp:98
Definition tricycle_controller.hpp:93
Definition tricycle_controller.hpp:118