I guess the adaptations that would have to be made in base_local_planner are managable. When you have a look at the files trajectory_planner.cpp and trajectory_planner.h, you will find the motion equations in the header file to be x(t+1) = x(t) + (v(x)cos(theta) + v(x)sin(theta))*dt, so the ones of a differantial drive robot. They are used within the function TrajectoryPlanner::generateTrajectory() and are simply sampled over a finite time horizon with given time resolution. So the only thing here would be to replace these equations with the ones of an ackermann steering vehicle (that is more or less introducing the steering speed, have a look e.g. at link to paper on how to describe such a system).
Furthermore, one should review the sampling of the input space: for differantial drive robots, it makes sense to sample longitudinal and rotational velocity, for ackermann vehicles it would make more sense to sample longitudinal velocity and steering speed, as this refers to the system's inputs. You will have to make these adaptions probably at quite a few places in the code, but mainly in trajectory_planner.cpp line 461-490. Also you would have to remove lines 532-574 to remove the sampling of in-place rotations. One could also remove the code for holonomic robots, but this can just be deactivated by a ros parameter.
As far as I see, these are the major changes to the code.
The sampled trajectories are then scored with respect to their proximity and alignment to the global path given by the base_global_planer, but it should not be necessary to change anything here.
One could even try for the beginning to use the standard base_global_planner (NavFn) and do the adaptions to the base_local_planner, but one would have to expect suboptimal behaviour, due to the fact that the global path does not respect the system's kinematics correctly.
Please correct me, if I am wrong.