53 using Twist = geometry_msgs::msg::Twist;
54 using TwistStamped = geometry_msgs::msg::TwistStamped;
55 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
58 TRICYCLE_CONTROLLER_PUBLIC
61 TRICYCLE_CONTROLLER_PUBLIC
64 TRICYCLE_CONTROLLER_PUBLIC
67 TRICYCLE_CONTROLLER_PUBLIC
68 controller_interface::return_type update()
override;
70 TRICYCLE_CONTROLLER_PUBLIC
71 controller_interface::return_type init(
const std::string & controller_name)
override;
73 TRICYCLE_CONTROLLER_PUBLIC
74 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
76 TRICYCLE_CONTROLLER_PUBLIC
77 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
79 TRICYCLE_CONTROLLER_PUBLIC
80 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
82 TRICYCLE_CONTROLLER_PUBLIC
83 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
85 TRICYCLE_CONTROLLER_PUBLIC
86 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
88 TRICYCLE_CONTROLLER_PUBLIC
89 CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state)
override;
94 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
95 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
99 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
100 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
103 CallbackReturn get_traction(
104 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
105 CallbackReturn get_steering(
106 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
107 double convert_trans_rot_vel_to_steering_angle(
double v,
double omega,
double wheelbase);
108 std::tuple<double, double> twist_to_ackermann(
double linear_command,
double angular_command);
110 std::string traction_joint_name_;
111 std::string steering_joint_name_;
114 std::vector<TractionHandle> traction_joint_;
115 std::vector<SteeringHandle> steering_joint_;
119 double wheelbase = 0.0;
125 bool open_loop =
false;
126 bool enable_odom_tf =
false;
127 bool odom_only_twist =
false;
128 std::string base_frame_id =
"base_link";
129 std::string odom_frame_id =
"odom";
130 std::array<double, 6> pose_covariance_diagonal;
131 std::array<double, 6> twist_covariance_diagonal;
134 bool publish_ackermann_command_ =
false;
135 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ =
nullptr;
136 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
137 realtime_ackermann_command_publisher_ =
nullptr;
141 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
142 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
143 realtime_odometry_publisher_ =
nullptr;
145 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
147 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
148 realtime_odometry_transform_publisher_ =
nullptr;
151 std::chrono::milliseconds cmd_vel_timeout_{500};
153 bool subscriber_is_active_ =
false;
154 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
155 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
156 velocity_command_unstamped_subscriber_ =
nullptr;
160 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
162 std::queue<AckermannDrive> previous_commands_;
165 TractionLimiter limiter_traction_;
166 SteeringLimiter limiter_steering_;
168 rclcpp::Time previous_update_timestamp_{0};
171 double publish_rate_ = 50.0;
172 rclcpp::Duration publish_period_{0, 0};
173 rclcpp::Time previous_publish_timestamp_{0};
175 bool is_halted =
false;
176 bool use_stamped_vel_ =
true;
179 const std::shared_ptr<rmw_request_id_t> request_header,
180 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
181 std::shared_ptr<std_srvs::srv::Empty::Response> res);