pvandervelde / zinger_swerve_controller

The swerve controller code for the zinger robot
Apache License 2.0
15 stars 6 forks source link

Setting acceleration #5

Open peterheim1 opened 1 month ago

peterheim1 commented 1 month ago

Hi where can i find and adjust the acceleration settings they are to low for my robot it take about 3 seconds to achieve the desired velocity

pvandervelde commented 1 month ago

There isn't really a place where the acceleration is set. Each time we get a new velocity command we create a new velocity profile to get to the new velocity (see here: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/swerve_controller.py#L212). Each profile is assumed to take 1 second (see line 221 in that file). So in a roundabout way that determines the acceleration (or at least the way the acceleration changes.

Additionally if you are using ROS there is a velocity and acceleration limit somewhere in the Nav part of ROS that might be holding back the acceleration.

To be honest I haven't really worked this out. The profiles are a bit rough and definitely leave performance on the table. :(

peterheim1 commented 1 month ago

ok im trying to get my hardware to work with your controller the hardware expects the velocity to be in m/s your output is scaled for a velocity of .17m/s input the controller give a output of about 4 to 5and it takes about 2 to 3 seconds to get there. if we reduce the scaled output to a smaller value would that get there quicker and if so where can i change it. im looking for a 0 to 0.17m/s in about 0.5 seconds i have a lot of problems with navigation(using my old controller) if the acceleration is to slow

pvandervelde commented 1 month ago

I'm not sure I follow. What you're saying is that you send a velocity command with a value of 4m/s and the robot maxes out at 0.17m/s? And it takes 3 seconds to get to 0.17 m/s

There is no velocity limit in the controller as far as I remember. The only thing I can think of is that the dimensions of the robot in the swerve_controller aren't correct. However the kinematics calculate the velocity of the wheel contact point (so the size of the wheel etc. aren't part of that calculation). The size of the robot base, or more specifically the distance between the wheels do matter.

The other thing you may be running into (which would be weird, but possible) is that the code limits the velocity of the wheel contact point to the maximum velocity defined here: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/swerve_controller.py#L273 (and further down for the other drive modules). The limiter code is here: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/control_model.py#L176. However the limit is set to 10 (m/s). So there should be plenty of room. In theory if you command a velocity of 10 m/s in a straight line it should just work.

I wonder if what you're running into is this: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/swerve_controller.py#L212? That comment came about from me having issues in Gazebo, getting the robot to move at any kind of speed. Using the linear profile sort of fixed it. But maybe that's still not good enough for the real world. If that's the case then I need to improve how the code handles profiles.

peterheim1 commented 4 days ago

i publish the velocity to 0.17 m/s on the cmd_vel topic the velocity published by the swerve drive controller is 4.0 m/s but it takes about 3 seconds to get there. my joint state publisher will publish the actual velocity of the wheel

"However the kinematics calculate the velocity of the wheel contact point" I'm not sure i fully under stand this would this be the same as the robot velocity?(all wheels being equal )

pvandervelde commented 4 days ago

So for 0.17 m/s with 10cm diameter wheels I think we should get 3.4 rad/s for the wheel speed. The velocity commands should be in radians / s if I am correct. So I think the value that is getting sent is about right. But I'm still confused as to why it would take 3 seconds to get to that speed. Looking at some of the rosbags that's also not what I'm seeing. For instance in first_3_0 the initial velocity command given is a linear velocity in the x-direction of 0.4 m/s. The robot accelerates to about 0.17m/s over a time of about 0.5 seconds (if I'm reading the data correctly).

image

left is joint_states (wheel velocities selected), right top is velocity commands sent and right bottom is cmd_vel with x-velocity in orange

Zooming in:

image

Are the velocities being sent by the joint_states correct? I'd expect them to be much larger?

pvandervelde commented 4 days ago

"However the kinematics calculate the velocity of the wheel contact point" I'm not sure i fully under stand this would this be the same as the robot velocity?(all wheels being equal )

Yes that would be what I meant, but the original statement is not entirely correct. The kinematics calculates the velocity of the robot at the point where the steering axle would meet the ground, but the code translates that to a wheel rotational velocity.

pvandervelde commented 4 days ago

Is the code that you're running on your robot here: https://github.com/peterheim1/omni_bot/tree/humble? I've been trying to figure out how it works and which part does the motor control and the calculation of the joint_states but I'm not sure I have found the correct bits.

peterheim1 commented 3 days ago

that code is a bit of a mess the joint_state publisher is in scripts/omni_controller.py in _Broadcast_Odom function it reads the values from the arduino sent via the the steering and vel topics sent to the arduino code its in firmware. the version that worked the best was the on where i scaled the velocity to PWM. the newer code is in https://github.com/peterheim1/omni_bot2/blob/main/scripts/controller.py over the week end i will rewrite the joint_states to reflect a rads/s value and see how that goes

peterheim1 commented 3 days ago

ok just so i can get my head straight if I set robot speed to .17m/s the controller converts this to rad/s the joint_state should reflect the current rad/s and the controller will adjust the next message in the joint velocity topic but this should be a small? the controller will use the joint_state values and publish a odom message and a TF. what hardware is your robot?

pvandervelde commented 2 days ago

This line: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/swerve_controller.py#L571 sets the value that will be sent for the velocity command. It divides the linear velocity (in m/s) by the radius of the wheel, so if I'm correct then that should result in a rotational velocity in rad/s.

pvandervelde commented 2 days ago

ok just so i can get my head straight if I set robot speed to .17m/s the controller converts this to rad/s the joint_state should reflect the current rad/s and the controller will adjust the next message in the joint velocity topic but this should be a small? the controller will use the joint_state values and publish a odom message and a TF. what hardware is your robot?

I don't have a robot yet :( I've been working on a design but I'm much better at typing code than I am at electronics and mechanical design so it's not going very quick.

peterheim1 commented 2 days ago

i just done a quick conversion to rad/s and fired up base launch in zinger description in rviz the wheels steer but they dont turn with the velocity cmd i think i may have have a misunderstanding in the joint_states layout below is my current one msg.name = [ 'joint_chassis_to_steering_left_front', 'joint_chassis_to_steering_left_rear', 'joint_chassis_to_steering_right_rear', 'joint_chassis_to_steering_right_front', 'joint_steering_to_wheel_left_front', 'joint_steering_to_wheel_left_rear', 'joint_steering_to_wheel_right_rear', 'joint_steering_to_wheel_right_front' ] msg.position = [ s1, s2, s3, s4, 0.0, 0.0, 0.0, 0.0 ] msg.velocity = [0.0, 0.0, 0.0, 0.0, v1, v2, v3, v4] msg.effort = [0.0] * 8

pvandervelde commented 2 days ago

Is it this line here: https://github.com/peterheim1/omni_bot2/blob/5fee1dd0fb601edc477d4d01b9718a9dd0e2922a/scripts/controller.py#L95 that you're talking about? If so what is in lineParts. I assume it's an array of numbers, but what do those numbers represent? Is it encoder ticks or ?

On my side the joint_state message is processed here: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/swerve_controller.py#L392. That grabs the steering angle (which should be in radians if I've written my code right) and the drive velocity (in rad/s) and stores those values. It will transform the drive velocity from rad/s to m/s by multiplying by the wheel radius (here: https://github.com/pvandervelde/zinger_swerve_controller/blob/b2f9b94da06e80566e4efe7623be1e5a393633fa/zinger_swerve_controller/swerve_controller.py#L421).

peterheim1 commented 2 days ago

lineParts are the values from the arduino MCU the first 4 are steering angles in degrees and the other 4 are wheel velocity i think in meters per cm * 100 so it goes over the MCU I2Cwith out errors. so in the joint_states for wheel velocity they are in position vel 5 6 7 8 and steering are in pos 1 2 3 4

pvandervelde commented 1 day ago

lineParts are the values from the arduino MCU the first 4 are steering angles in degrees and the other 4 are wheel velocity i think in meters per cm * 100 so it goes over the MCU I2Cwith out errors. so in the joint_states for wheel velocity they are in position vel 5 6 7 8 and steering are in pos 1 2 3 4

in joint_states you could have positions for the wheels as well if you wanted to. I don't think the code uses those though.

I'm not sure I understand the wheel velocity in meters per cm though. I guess that's rotations?

peterheim1 commented 1 day ago

I'm not sure I understand the wheel velocity in meters per cm though. I guess that's rotations?

the instrument i use the check the wheel speed is in cm/s and the I2C bus likes integers not floats a little bit of extra maths and its what ever you want it.

in joint_states you could have positions for the wheels as well if you wanted to. I don't think the code uses those though.

with my simple odom publisher a difference in wheel angles between programmed and real makes a large difference in the final localization robot. so much so i had to upgrade the wheel position encoder from pots the magnetic encoders and add IMU YAW angle