57 using Twist = geometry_msgs::msg::Twist;
58 using TwistStamped = geometry_msgs::msg::TwistStamped;
59 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
62 TRICYCLE_CONTROLLER_PUBLIC
65 TRICYCLE_CONTROLLER_PUBLIC
68 TRICYCLE_CONTROLLER_PUBLIC
71 TRICYCLE_CONTROLLER_PUBLIC
72 controller_interface::return_type
update(
73 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
75 TRICYCLE_CONTROLLER_PUBLIC
76 CallbackReturn
on_init()
override;
78 TRICYCLE_CONTROLLER_PUBLIC
79 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
81 TRICYCLE_CONTROLLER_PUBLIC
82 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
84 TRICYCLE_CONTROLLER_PUBLIC
85 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
87 TRICYCLE_CONTROLLER_PUBLIC
88 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
90 TRICYCLE_CONTROLLER_PUBLIC
91 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
93 TRICYCLE_CONTROLLER_PUBLIC
94 CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state)
override;
99 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
100 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
104 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
105 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
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);
116 std::shared_ptr<ParamListener> param_listener_;
120 std::vector<TractionHandle> traction_joint_;
121 std::vector<SteeringHandle> steering_joint_;
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;
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;
133 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
135 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
136 realtime_odometry_transform_publisher_ =
nullptr;
139 std::chrono::milliseconds cmd_vel_timeout_{500};
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;
148 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
150 std::queue<AckermannDrive> previous_commands_;
153 TractionLimiter limiter_traction_;
154 SteeringLimiter limiter_steering_;
156 bool is_halted =
false;
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);