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