54 using Twist = geometry_msgs::msg::Twist;
55 using TwistStamped = geometry_msgs::msg::TwistStamped;
56 using AckermannDrive = ackermann_msgs::msg::AckermannDrive;
65 controller_interface::return_type
update(
66 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
68 CallbackReturn
on_init()
override;
70 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
72 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
74 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
76 CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & previous_state)
override;
78 CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state)
override;
81 const std::shared_ptr<rmw_request_id_t> request_header,
82 const std::shared_ptr<std_srvs::srv::Empty::Request> req,
83 std::shared_ptr<std_srvs::srv::Empty::Response> res);
88 std::reference_wrapper<const hardware_interface::LoanedStateInterface> velocity_state;
89 std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity_command;
93 std::reference_wrapper<const hardware_interface::LoanedStateInterface> position_state;
94 std::reference_wrapper<hardware_interface::LoanedCommandInterface> position_command;
97 CallbackReturn get_traction(
98 const std::string & traction_joint_name, std::vector<TractionHandle> & joint);
99 CallbackReturn get_steering(
100 const std::string & steering_joint_name, std::vector<SteeringHandle> & joint);
101 double convert_trans_rot_vel_to_steering_angle(
double v,
double omega,
double wheelbase);
102 std::tuple<double, double> twist_to_ackermann(
double linear_command,
double angular_command);
105 std::shared_ptr<ParamListener> param_listener_;
109 std::vector<TractionHandle> traction_joint_;
110 std::vector<SteeringHandle> steering_joint_;
112 std::shared_ptr<rclcpp::Publisher<AckermannDrive>> ackermann_command_publisher_ =
nullptr;
113 std::shared_ptr<realtime_tools::RealtimePublisher<AckermannDrive>>
114 realtime_ackermann_command_publisher_ =
nullptr;
115 AckermannDrive ackermann_command_msg_;
119 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ =
nullptr;
120 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
121 realtime_odometry_publisher_ =
nullptr;
122 nav_msgs::msg::Odometry odometry_msg_;
124 std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
126 std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
127 realtime_odometry_transform_publisher_ =
nullptr;
128 tf2_msgs::msg::TFMessage tf_msg_;
131 std::chrono::milliseconds cmd_vel_timeout_{500};
133 bool subscriber_is_active_ =
false;
134 rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ =
nullptr;
138 std::shared_ptr<TwistStamped> last_command_msg_;
140 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;
141 std::atomic<bool> reset_odom_{
false};
143 std::queue<AckermannDrive> previous_commands_;
146 TractionLimiter limiter_traction_;
147 SteeringLimiter limiter_steering_;