Dear Huzaifa,

Thank you so much! This is the link to my code:
https://github.com/UraraKono/pychrono-steering
Could you first look at the README file to get the overview of my code?
Please run main.py.

Best regards,
Urara

On Mon, Nov 6, 2023 at 1:02 PM 'HUZAIFA MUSTAFA UNJHAWALA' via
ProjectChrono <[email protected]> wrote:

> Hello Urara,
>
> The code I provided for toe_in_r is what I suppose is the \delta from your
> image. However note that the vehicles in PyChrono are 4 wheeled, so you
> might need to make an approximation to get the \delta from the image (maybe
> take the average).
> That being said, from your plot, it is surprising that the rear tires have
> a toe angle and the angle keeps decreasing. Can you please post here the
> snippet of code that generated the data for the plots? I can try taking a
> quick look and reproduce this on my end.
>
> Best
> Huzaifa
>
> On Friday, November 3, 2023 at 11:03:56 AM UTC-5 [email protected]
> wrote:
>
>> Hello,
>>
>> Thank you so much for the reply!
>> By "steering velocity and acceleration", I meant the steering angular
>> velocity of the tires and the longitudinal acceleration of the vehicle body.
>>
>> I tried your code in Pychrono.
>> However, even though I set the driver's steering input to be always "1"
>> so that the vehicle keeps turning anti-clock-wise, the toe_in_r of all four
>> wheels kept decreasing as shown in "toe-in.png".
>> The trajectory is shown in "trajectory.png". The vehicle starts from
>> (0,0) and keeps turning to the left.
>> Maybe the toe-in obtained from your code is still in the global frame?
>>
>> Is toe_in_r equivalent to "δ" in the screenshot of the vehicle model
>> figure attached to this email?
>> I want to obtain this "δ".
>>
>> Best regards,
>> Urara
>>
>>
>>
>>
>> On Wednesday, November 1, 2023 at 9:55:12 AM UTC-4 [email protected]
>> wrote:
>>
>>> 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 a topic in the
> Google Groups "ProjectChrono" group.
> To unsubscribe from this topic, visit
> https://groups.google.com/d/topic/projectchrono/bGrK7NFxsBI/unsubscribe
> <https://urldefense.com/v3/__https://groups.google.com/d/topic/projectchrono/bGrK7NFxsBI/unsubscribe__;!!IBzWLUs!VEreeTZm1KgpDeiWYmCTDRYWhiKJqfzXDEKYU59kbFDJ_2ZcUm7gnZiztNrlSdmlWbNvWiYj1gv6pD9ZozBOiFn11u021xw$>
> .
> To unsubscribe from this group and all its topics, send an email to
> [email protected].
> To view this discussion on the web visit
> https://groups.google.com/d/msgid/projectchrono/235b7608-63bb-46a4-91e0-0f27f75e0e06n%40googlegroups.com
> <https://urldefense.com/v3/__https://groups.google.com/d/msgid/projectchrono/235b7608-63bb-46a4-91e0-0f27f75e0e06n*40googlegroups.com?utm_medium=email&utm_source=footer__;JQ!!IBzWLUs!VEreeTZm1KgpDeiWYmCTDRYWhiKJqfzXDEKYU59kbFDJ_2ZcUm7gnZiztNrlSdmlWbNvWiYj1gv6pD9ZozBOiFn1bxQTjlE$>
> .
>


-- 
*Urara Kono*, Ph.D. student
GRASP Laboratory <https://www.grasp.upenn.edu>
Electrical and Systems Engineering
University of Pennsylvania
she/her/hers

-- 
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/CALLEzkPan1ASynXNTe23Rr5%2B03GPfh8XH2SN1%3DRJ-RJWXgVuug%40mail.gmail.com.

Reply via email to