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(
69 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
71 TRICYCLE_CONTROLLER_PUBLIC
72 CallbackReturn
on_init()
override;
74 TRICYCLE_CONTROLLER_PUBLIC
75 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
77 TRICYCLE_CONTROLLER_PUBLIC
78 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
80 TRICYCLE_CONTROLLER_PUBLIC
81 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
83 TRICYCLE_CONTROLLER_PUBLIC
84 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
86 TRICYCLE_CONTROLLER_PUBLIC
87 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
89 TRICYCLE_CONTROLLER_PUBLIC
90 CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & previous_state)
override;
95 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
96 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
100 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
101 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
104 CallbackReturn get_traction(
105 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
106 CallbackReturn get_steering(
107 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
108 double convert_trans_rot_vel_to_steering_angle(
double v,
double omega,
double wheelbase);
109 std::tuple<double, double> twist_to_ackermann(
double linear_command,
double angular_command);
111 std::string traction_joint_name_;
112 std::string steering_joint_name_;
115 std::vector<TractionHandle> traction_joint_;
116 std::vector<SteeringHandle> steering_joint_;
120 double wheelbase = 0.0;
126 bool open_loop =
false;
127 bool enable_odom_tf =
false;
128 bool odom_only_twist =
false;
129 std::string base_frame_id =
"base_link";
130 std::string odom_frame_id =
"odom";
131 std::array<double, 6> pose_covariance_diagonal;
132 std::array<double, 6> twist_covariance_diagonal;
135 bool publish_ackermann_command_ =
false;
136 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ =
nullptr;
137 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
138 realtime_ackermann_command_publisher_ =
nullptr;
142 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
143 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
144 realtime_odometry_publisher_ =
nullptr;
146 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
148 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
149 realtime_odometry_transform_publisher_ =
nullptr;
152 std::chrono::milliseconds cmd_vel_timeout_{500};
154 bool subscriber_is_active_ =
false;
155 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
156 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
157 velocity_command_unstamped_subscriber_ =
nullptr;
161 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
163 std::queue<AckermannDrive> previous_commands_;
166 TractionLimiter limiter_traction_;
167 SteeringLimiter limiter_steering_;
169 bool is_halted =
false;
170 bool use_stamped_vel_ =
true;
173 const std::shared_ptr<rmw_request_id_t> request_header,
174 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
175 std::shared_ptr<std_srvs::srv::Empty::Response> res);