ros2_control - humble
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
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 <tuple>
28#include <vector>
29
30#include "ackermann_msgs/msg/ackermann_drive.hpp"
31#include "controller_interface/controller_interface.hpp"
32#include "geometry_msgs/msg/twist.hpp"
33#include "geometry_msgs/msg/twist_stamped.hpp"
34#include "hardware_interface/handle.hpp"
35#include "nav_msgs/msg/odometry.hpp"
36#include "rclcpp/rclcpp.hpp"
37#include "rclcpp_lifecycle/state.hpp"
38#include "realtime_tools/realtime_box.hpp"
39#include "realtime_tools/realtime_publisher.hpp"
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
63
64 TRICYCLE_CONTROLLER_PUBLIC
66
67 TRICYCLE_CONTROLLER_PUBLIC
68 controller_interface::return_type update(
69 const rclcpp::Time & time, const rclcpp::Duration & period) override;
70
71 TRICYCLE_CONTROLLER_PUBLIC
72 CallbackReturn on_init() override;
73
74 TRICYCLE_CONTROLLER_PUBLIC
75 CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;
76
77 TRICYCLE_CONTROLLER_PUBLIC
78 CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
79
80 TRICYCLE_CONTROLLER_PUBLIC
81 CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
82
83 TRICYCLE_CONTROLLER_PUBLIC
84 CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;
85
86 TRICYCLE_CONTROLLER_PUBLIC
87 CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
88
89 TRICYCLE_CONTROLLER_PUBLIC
90 CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
91
92protected:
94 {
95 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
96 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
97 };
99 {
100 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
101 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
102 };
103
104 CallbackReturn get_traction(
105 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
106 CallbackReturn get_steering(
107 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
108 double convert_trans_rot_vel_to_steering_angle(double v, double omega, double wheelbase);
109 std::tuple<double, double> twist_to_ackermann(double linear_command, double angular_command);
110
111 std::string traction_joint_name_;
112 std::string steering_joint_name_;
113
114 // HACK: put into vector to avoid initializing structs because they have no default constructors
115 std::vector<TractionHandle> traction_joint_;
116 std::vector<SteeringHandle> steering_joint_;
117
119 {
120 double wheelbase = 0.0;
121 double radius = 0.0;
122 } wheel_params_;
123
125 {
126 bool open_loop = false;
127 bool enable_odom_tf = false;
128 bool odom_only_twist = false; // for doing the pose integration in separate node
129 std::string base_frame_id = "base_link";
130 std::string odom_frame_id = "odom";
131 std::array<double, 6> pose_covariance_diagonal;
132 std::array<double, 6> twist_covariance_diagonal;
133 } odom_params_;
134
135 bool publish_ackermann_command_ = false;
136 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ = nullptr;
137 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
138 realtime_ackermann_command_publisher_ = nullptr;
139
140 Odometry odometry_;
141
142 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
143 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
144 realtime_odometry_publisher_ = nullptr;
145
146 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
147 nullptr;
148 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
149 realtime_odometry_transform_publisher_ = nullptr;
150
151 // Timeout to consider cmd_vel commands old
152 std::chrono::milliseconds cmd_vel_timeout_{500};
153
154 bool subscriber_is_active_ = false;
155 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
156 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
157 velocity_command_unstamped_subscriber_ = nullptr;
158
159 realtime_tools::RealtimeBox<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr};
160
161 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
162
163 std::queue<AckermannDrive> previous_commands_; // last two commands
164
165 // speed limiters
166 TractionLimiter limiter_traction_;
167 SteeringLimiter limiter_steering_;
168
169 bool is_halted = false;
170 bool use_stamped_vel_ = true;
171
172 void reset_odometry(
173 const std::shared_ptr<rmw_request_id_t> request_header,
174 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
175 std::shared_ptr<std_srvs::srv::Empty::Response> res);
176 bool reset();
177 void halt();
178};
179} // namespace tricycle_controller
180#endif // TRICYCLE_CONTROLLER__TRICYCLE_CONTROLLER_HPP_
Definition controller_interface.hpp:29
Definition realtime_box.hpp:60
Definition odometry.hpp:30
Definition tricycle_controller.hpp:52
TRICYCLE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition tricycle_controller.cpp:109
TRICYCLE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition tricycle_controller.cpp:100
TRICYCLE_CONTROLLER_PUBLIC CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition tricycle_controller.cpp:51
TRICYCLE_CONTROLLER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition tricycle_controller.cpp:118
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56
Definition tricycle_controller.hpp:125
Definition tricycle_controller.hpp:99
Definition tricycle_controller.hpp:94
Definition tricycle_controller.hpp:119