ros2_control - iron
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.h"
39#include "realtime_tools/realtime_buffer.h"
40#include "realtime_tools/realtime_publisher.h"
41#include "std_srvs/srv/empty.hpp"
42#include "tf2_msgs/msg/tf_message.hpp"
43#include "tricycle_controller/odometry.hpp"
44#include "tricycle_controller/steering_limiter.hpp"
45#include "tricycle_controller/traction_limiter.hpp"
46#include "tricycle_controller/visibility_control.h"
47
48// auto-generated by generate_parameter_library
49#include "tricycle_controller_parameters.hpp"
50
51namespace tricycle_controller
52{
53using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
54
56{
57 using Twist = geometry_msgs::msg::Twist;
58 using TwistStamped = geometry_msgs::msg::TwistStamped;
59 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
60
61public:
62 TRICYCLE_CONTROLLER_PUBLIC
64
65 TRICYCLE_CONTROLLER_PUBLIC
67
68 TRICYCLE_CONTROLLER_PUBLIC
70
71 TRICYCLE_CONTROLLER_PUBLIC
72 controller_interface::return_type update(
73 const rclcpp::Time & time, const rclcpp::Duration & period) override;
74
75 TRICYCLE_CONTROLLER_PUBLIC
76 CallbackReturn on_init() override;
77
78 TRICYCLE_CONTROLLER_PUBLIC
79 CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;
80
81 TRICYCLE_CONTROLLER_PUBLIC
82 CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
83
84 TRICYCLE_CONTROLLER_PUBLIC
85 CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
86
87 TRICYCLE_CONTROLLER_PUBLIC
88 CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override;
89
90 TRICYCLE_CONTROLLER_PUBLIC
91 CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
92
93 TRICYCLE_CONTROLLER_PUBLIC
94 CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
95
96protected:
98 {
99 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
100 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
101 };
103 {
104 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
105 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
106 };
107
108 CallbackReturn get_traction(
109 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
110 CallbackReturn get_steering(
111 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
112 double convert_trans_rot_vel_to_steering_angle(double v, double omega, double wheelbase);
113 std::tuple<double, double> twist_to_ackermann(double linear_command, double angular_command);
114
115 // Parameters from ROS for tricycle_controller
116 std::shared_ptr<ParamListener> param_listener_;
117 Params params_;
118
119 // HACK: put into vector to avoid initializing structs because they have no default constructors
120 std::vector<TractionHandle> traction_joint_;
121 std::vector<SteeringHandle> steering_joint_;
122
123 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ = nullptr;
124 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
125 realtime_ackermann_command_publisher_ = nullptr;
126
127 Odometry odometry_;
128
129 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
130 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
131 realtime_odometry_publisher_ = nullptr;
132
133 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
134 nullptr;
135 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
136 realtime_odometry_transform_publisher_ = nullptr;
137
138 // Timeout to consider cmd_vel commands old
139 std::chrono::milliseconds cmd_vel_timeout_{500};
140
141 bool subscriber_is_active_ = false;
142 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;
143 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
144 velocity_command_unstamped_subscriber_ = nullptr;
145
146 realtime_tools::RealtimeBox<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr};
147
148 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
149
150 std::queue<AckermannDrive> previous_commands_; // last two commands
151
152 // speed limiters
153 TractionLimiter limiter_traction_;
154 SteeringLimiter limiter_steering_;
155
156 bool is_halted = false;
157
158 void reset_odometry(
159 const std::shared_ptr<rmw_request_id_t> request_header,
160 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
161 std::shared_ptr<std_srvs::srv::Empty::Response> res);
162 bool reset();
163 void halt();
164};
165} // namespace tricycle_controller
166#endif // TRICYCLE_CONTROLLER__TRICYCLE_CONTROLLER_HPP_
Definition controller_interface.hpp:29
Definition realtime_box.hpp:60
Definition odometry.hpp:30
Definition tricycle_controller.hpp:56
TRICYCLE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition tricycle_controller.cpp:77
TRICYCLE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition tricycle_controller.cpp:68
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:86
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56
Definition tricycle_controller.hpp:103
Definition tricycle_controller.hpp:98