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