54 using Twist = geometry_msgs::msg::Twist;
55 using TwistStamped = geometry_msgs::msg::TwistStamped;
56 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
59 TRICYCLE_CONTROLLER_PUBLIC
62 TRICYCLE_CONTROLLER_PUBLIC
65 TRICYCLE_CONTROLLER_PUBLIC
68 TRICYCLE_CONTROLLER_PUBLIC
69 controller_interface::return_type
update(
70 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
72 TRICYCLE_CONTROLLER_PUBLIC
73 CallbackReturn
on_init()
override;
75 TRICYCLE_CONTROLLER_PUBLIC
76 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
78 TRICYCLE_CONTROLLER_PUBLIC
79 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
81 TRICYCLE_CONTROLLER_PUBLIC
82 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
84 TRICYCLE_CONTROLLER_PUBLIC
85 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
87 TRICYCLE_CONTROLLER_PUBLIC
88 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
93 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
94 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
98 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
99 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
102 CallbackReturn get_traction(
103 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
104 CallbackReturn get_steering(
105 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
106 double convert_trans_rot_vel_to_steering_angle(
double v,
double omega,
double wheelbase);
107 std::tuple<double, double> twist_to_ackermann(
double linear_command,
double angular_command);
109 std::string traction_joint_name_;
110 std::string steering_joint_name_;
113 std::vector<TractionHandle> traction_joint_;
114 std::vector<SteeringHandle> steering_joint_;
118 double wheelbase = 0.0;
124 bool open_loop =
false;
125 bool enable_odom_tf =
false;
126 bool odom_only_twist =
false;
127 std::string base_frame_id =
"base_link";
128 std::string odom_frame_id =
"odom";
129 std::array<double, 6> pose_covariance_diagonal;
130 std::array<double, 6> twist_covariance_diagonal;
133 bool publish_ackermann_command_ =
false;
134 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ =
nullptr;
135 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
136 realtime_ackermann_command_publisher_ =
nullptr;
140 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
141 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
142 realtime_odometry_publisher_ =
nullptr;
144 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
146 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
147 realtime_odometry_transform_publisher_ =
nullptr;
150 std::chrono::milliseconds cmd_vel_timeout_{500};
152 bool subscriber_is_active_ =
false;
153 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
154 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
155 velocity_command_unstamped_subscriber_ =
nullptr;
159 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
161 std::queue<AckermannDrive> previous_commands_;
164 TractionLimiter limiter_traction_;
165 SteeringLimiter limiter_steering_;
167 bool is_halted =
false;
168 bool use_stamped_vel_ =
true;
171 const std::shared_ptr<rmw_request_id_t> request_header,
172 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
173 std::shared_ptr<std_srvs::srv::Empty::Response> res);