![]() |
Straffing Issue
Okay so everything is working. Currently the left joyx on our XBox controller is straffing and the left joyy on the controller is forwards/backwards. The straffing is inverted - if I push the joystick left it goes right and vice versa. Also it is REALLY slow while straffing. The mecanumDrive function is in the subsystem Mecanum and the values are passed to it in the DriveTele command
I inverted the values already because at first forwards/backwards was inverted and straffing was good - but when I inverted it forwards/backwards was right and straffing was inverted Does anyone have any ideas on how to invert the straffing and increase its speed? Here is the code: https://github.com/MrSTUDofCODE/NewM...team4623/robot THANKS! |
Re: Straffing Issue
Quote:
|
Re: Straffing Issue
Quote:
check every single one of the rollers on each of the four wheels to make sure they spin freely. |
Re: Straffing Issue
Quote:
Code:
Robot.mec.mecanumDrive(Code:
public void mecanumDrive(double FL, double RL, double FR, double RR) {In the case of strafe right, X will be 1.0 so your 4 values become FL=0.5 RL=-0.5 FR=+0.5 RR=-0.5 You then negate all of these for the motors so the motors see frontLeft -0.5 rearLeft +0.5 frontRight -0.5 rearRight +0.5 Because those on the right side are likely driving in reverse on positive voltage this is most likely frontLeft toward robot rear 0.5 rearLeft toward robot fore 0.5 frontRight toward robot fore 0.5 rearRight toward robot rear 0.5 which unfortunately is the way to rotate wheels for strafing left. So as Ether says, change the +/- in front of all your getX() calls in your DriveTele and this will solve the problem. To fix your speed issue you need to do something different than (X + Y)/2.0. (X+Y)/2.0 gives you 1.0 only on the diagonals, but not straight ahead or to the sides. If you have studied polar math in school, you should know that a better formulation for what you are trying to do is to combine the two into a magnitude with sqrt(x*x + y*y) via the Pythagorean theorem. This way straight left calculates sqrt(1+0) = 1.0. And sqrt(0.5*0.5 + 0.5*0.5) = 0.5. But then to get your signs right, you have to compensate. based on the sign of x and y. I would recommend that you instantiate a RobotDrive object in your subsystem and call the mecanumDrive_Cartesian(x,y,rot,gyro) function-- you can pass 0 in for rotation and the gyro. Then you can just pass getX and getY from your stick. Code:
Code:
Good luck! |
Yeah, just negate the axis values you are using to strafe. Also, strafing requires more torque than moving normally, so its normal to be moving more slowly. If you want to move more effectively sideways, then gear your drivetrain for torque.
|
Re: Straffing Issue
Okay I that fixed the straffing inverted issue but it still does not go faster with cartesian - and if I try multiplying the values everything gets screwed up
|
Re: Straffing Issue
Quote:
Quote:
|
Re: Straffing Issue
Quote:
I looked at your Github code which was updated about 24 hours ago and it still looks like you are sending 0.5 power to all your motors while strafing. |
| All times are GMT -5. The time now is 22:28. |
Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi