Hello,

Do you want to get the angle by which the tire-wheel steers? GetSteering 
will only give you the normalized steering input (between -1 and 1) that 
the driver applies onto the steering wheel at the current time step. 
If you would like to get the tire-wheel steer angle, you could do something 
like this

            // Get the right wheel state
            auto state = vehicle.GetWheel(0, 
VehicleSide{RIGHT})->GetState();
            // Wheel normal (expressed in global frame)
            ChVector<> wheel_normal = state.rot.GetYaxis();

            // Terrain normal at wheel location (expressed in global frame)
            ChVector<> Z_dir = terrain.GetNormal(state.pos);

            // Longitudinal (heading) and lateral directions, in the 
terrain plane
            ChVector<> X_dir = Vcross(wheel_normal, Z_dir);
            X_dir.Normalize();
            ChVector<> Y_dir = Vcross(Z_dir, X_dir);

            // Tire reference coordinate system
            ChMatrix33<> rot;
            rot.Set_A_axis(X_dir, Y_dir, Z_dir);
            ChCoordsys<> tire_csys(state.pos, rot.Get_A_quaternion());

            // Express wheel normal in tire frame
            ChVector<> n = 
tire_csys.TransformDirectionParentToLocal(wheel_normal);

            // Wheel normal in the Vehicle frame
            ChVector<> n_v = 
vehicle.GetTransform().TransformDirectionParentToLocal(wheel_normal);

            // Toe-in
            auto toe_in_r = std::atan2(n_v.x(), n_v.y());

However, I do not understand what you mean by "steering velocity and 
acceleration", do you want to control the lateral velocity and acceleration 
of the vehicle? 





On Monday, October 23, 2023 at 9:23:40 AM UTC-5 [email protected] wrote:

> Hello,
>
> Thank you so much for providing this wonderful simulator.
> I'm new to Pychrono and I have a question.
>
> I'm trying to modify demo_VEH_SteeringController.py so that the vehicle 
> can accept steering velocity and acceleration commands. I want to convert 
> these two commands into throttle, brake, and steering input. 
> ChPathFillowerDriver has GetSteering to get the driver steering *input,* 
> but how can I get the *current actual *steering angle so that I can 
> implement a PID controller for the steering?
>
> Or in this simulation, is it assumed that the driver steering input is 
> always the same as the actual steering?
>
> Best regards,
> Urara
>

-- 
You received this message because you are subscribed to the Google Groups 
"ProjectChrono" group.
To unsubscribe from this group and stop receiving emails from it, send an email 
to [email protected].
To view this discussion on the web visit 
https://groups.google.com/d/msgid/projectchrono/d2270216-a572-4ed2-b790-0ebf7c504b2en%40googlegroups.com.

Reply via email to