53 using Twist = geometry_msgs::msg::Twist;
54 using TwistStamped = geometry_msgs::msg::TwistStamped;
55 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
64 controller_interface::return_type
update(
65 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
67 CallbackReturn
on_init()
override;
69 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
71 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
73 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
75 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
77 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
82 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
83 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
87 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
88 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
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);
99 std::shared_ptr<ParamListener> param_listener_;
103 std::vector<TractionHandle> traction_joint_;
104 std::vector<SteeringHandle> steering_joint_;
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;
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;
116 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
118 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
119 realtime_odometry_transform_publisher_ =
nullptr;
122 std::chrono::milliseconds cmd_vel_timeout_{500};
124 bool subscriber_is_active_ =
false;
125 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
128 std::shared_ptr<TwistStamped> last_command_msg_;
130 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
132 std::queue<AckermannDrive> previous_commands_;
135 TractionLimiter limiter_traction_;
136 SteeringLimiter limiter_steering_;
138 bool is_halted =
false;
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);