Chief Delphi

Chief Delphi (http://www.chiefdelphi.com/forums/index.php)
-   Programming (http://www.chiefdelphi.com/forums/forumdisplay.php?f=51)
-   -   Talon SRX spamming forward and backward constantly (http://www.chiefdelphi.com/forums/showthread.php?t=133884)

Wenry_Hill 03-02-2015 20:45

Re: Talon SRX spamming forward and backward constantly
 
Quote:

Originally Posted by ozrien (Post 1437938)
There is definitely something wrong with that robot app. Running it on my bot it looks like two things are trying to drive all the Talons, it keeps switching between zero and nonzero values. I'll keep digging...

Wow thanks, over here we're fairly lost. If you're robot is working fine with your code, can you send us the drive part to see if it's in our code or hardware? And thanks again for all the help.

ozrien 03-02-2015 21:09

Re: Talon SRX spamming forward and backward constantly
 
Well to sanity checks things I grabbed the stock example at ...
http://wpilib.screenstepslive.com/s/...-mecanum-drive

...and tweaked it a bit. It is just mechanum drive with CANTalons and no gyro. I...

-changed the Talons to CANTalons and used 1,3,4,5 for the device IDs to match your bot. Although I did NOT cross-reference your code to make sure the number-to-positions matched (LF,LR,RF,RR).
-I increased the motor safety timeout to 500ms. Seems like the default is not long enough to cover the time between enabling and getting to the first TeleopOpLoop.
-Changed the joystick index to 0 from 1.

To use this example just create a new IterativeRobot and paste this into Robot.cpp.


Code:

#include "WPILib.h"/**
 * Simplest program to drive a robot with mecanum drive using a single Logitech
 * Extreme 3D Pro joystick and 4 drive motors connected as follows:
 *  - Digital Sidecar 1:
 *    - PWM 1 - Connected to front left drive motor
 *    - PWM 2 - Connected to rear left drive motor
 *    - PWM 3 - Connected to front right drive motor
 *    - PWM 4 - Connected to rear right drive motor
 */
class MecanumDefaultCode : public IterativeRobot
{
        CANTalon lf; /*left front */
        CANTalon lr;/*left rear */
        CANTalon rf; /*right front */
        CANTalon rr; /*right rear */
public:
        RobotDrive *m_robotDrive;                // RobotDrive object using PWM 1-4 for drive motors
        Joystick *m_driveStick;                        // Joystick object on USB port 1 (mecanum drive)public:
        /**
        * Constructor for this "MecanumDefaultCode" Class.
        */
        MecanumDefaultCode(void) : lf(1), lr(3), rf(4), rr(5)
        {
                /* Set every Talon to reset the motor safety timeout. */
                lf.Set(0);
                lr.Set(0);
                rf.Set(0);
                rr.Set(0);
                // Create a RobotDrive object using PWMS 1, 2, 3, and 4
                m_robotDrive = new RobotDrive(lf, lr, rf, rr);
                m_robotDrive->SetExpiration(0.5);
                // Define joystick being used at USB port #0 on the Drivers Station
                m_driveStick = new Joystick(0);
                // Twist is on Axis 3 for the Extreme 3D Pro
                m_driveStick->SetAxisChannel(Joystick::kTwistAxis, 3);
        }
        /**
        * Gets called once for each new packet from the DS.
        */
        void TeleopPeriodic(void)
        {
                m_robotDrive->MecanumDrive_Cartesian(m_driveStick->GetX(), m_driveStick->GetY(), m_driveStick->GetTwist());
        }
};
START_ROBOT_CLASS(MecanumDefaultCode);


Alan Anderson 03-02-2015 22:01

Re: Talon SRX spamming forward and backward constantly
 
If you don't have any load on the drive wheels when you try to control the speed in closed-loop mode, you're very likely to get wildly oscillating wheels as they overshoot the target speed and try to correct.

Try giving them some load, like a patch of carpet pressed lightly against the rollers. You might also try adding some rate limiting on the motor power to keep it from thrashing so badly.

Wenry_Hill 03-02-2015 22:56

Re: Talon SRX spamming forward and backward constantly
 
Our head mentor uploaded some new code to get and it seemed to work. However the controls are off. See the video. https://www.youtube.com/watch?v=uDY6QJa7FKw Thanks everyone for there help and especially ozrien for putting the code on your robot. Tomorrow I'll post how he was able to fix it but for now sleep and class.

ozrien 03-02-2015 23:25

Re: Talon SRX spamming forward and backward constantly
 
Got this working on my bot. I used 3,1,4,5 for LeftFront, LeftRear, RightFront, RightRear respectively. Also added gyro an analog0 so holds absolute angle.
-I use the F350-similar gamepad (the wireless version), so I changed the three axes to X,Y,Z.
-Also I added button5 so that it will reset angle, thus allowing you to reselect the angle heading to servo to.
-Also inverted my right side since right-side motors have to drive negative (red) to move robot forward.

Actually I've been playing with this for about half an hour, driving it around the CTR office, so it seems pretty good.

Code:

#include "WPILib.h"
class MecanumDefaultCode : public IterativeRobot
{
        CANTalon lf; /*left front */
        CANTalon lr;/*left rear */
        CANTalon rf; /*right front */
        CANTalon rr; /*right rear */
public:
        RobotDrive *m_robotDrive;                // RobotDrive object using PWM 1-4 for drive motors
        Joystick *m_driveStick;                        // Joystick object on USB port 1 (mecanum drive)public:
        Gyro gyro;
        /**
        * Constructor for this "MecanumDefaultCode" Class.
        */
        MecanumDefaultCode(void) : lf(3), lr(1), rf(4), rr(5), gyro(0)
        {
                /* Set every Talon to reset the motor safety timeout. */
                lf.Set(0);
                lr.Set(0);
                rf.Set(0);
                rr.Set(0);
                // Create a RobotDrive object using PWMS 1, 2, 3, and 4
                m_robotDrive = new RobotDrive(lf, lr, rf, rr);
                m_robotDrive->SetExpiration(0.5);
                m_robotDrive->SetSafetyEnabled(false);
                // Define joystick being used at USB port #0 on the Drivers Station
                m_driveStick = new Joystick(0);
        }
        void TeleopInit()
        {
                gyro.Reset();
        }
        /** @return 10% deadband */
        double Db(double axisVal)
        {
                if(axisVal < -0.10)
                        return axisVal;
                if(axisVal > +0.10)
                        return axisVal;
                return 0;
        }
        /**
        * Gets called once for each new packet from the DS.
        */
        void TeleopPeriodic(void)
        {
                float angle = gyro.GetAngle();
                //std::cout << "Angle : " << angle << std::endl;
                m_robotDrive->MecanumDrive_Cartesian(        Db(m_driveStick->GetX()),
                                                                                                Db(m_driveStick->GetY()),
                                                                                                Db(m_driveStick->GetZ()),
                                                                                                angle);
                /* my right side motors need to drive negative to move robot forward */
                m_robotDrive->SetInvertedMotor(RobotDrive::kFrontRightMotor,true);
                m_robotDrive->SetInvertedMotor(RobotDrive::kRearRightMotor,true);
                /* on button 5, reset gyro angle to zero */
                if(m_driveStick->GetRawButton(5))
                        gyro.Reset();
        }
};
START_ROBOT_CLASS(MecanumDefaultCode);


DonRotolo 04-02-2015 09:07

Re: Talon SRX spamming forward and backward constantly
 
Quote:

Originally Posted by Wenry_Hill (Post 1438015)
but for now sleep and class.

(Off topic) Sorry, I couldn't let this pass by. Sleep and Class seem to go together, eh?

ozrien 04-02-2015 14:54

Re: Talon SRX spamming forward and backward constantly
 
Quote:

Originally Posted by GeeTwo (Post 1437524)
My spitball guess is that both Talons have the same CAN address, and one is on the left side of the robot, and the other is on the right side of the robot. When you send the command, both motors respond by rotating in the same direction. However, as the motors are oriented in opposite directions, one of them appears to be going backward.

This cannot happen...
Quote:

Although the roboRIO Web-based Configuration is tolerant of “common ID” Talon SRXs to a
point, the robot programming API will not enable/control “common ID” Talons reliably.
...section 3.1 in Talon SRX Software Reference Manual.

Basically two Common-ID talons can't be enabled at the same time. One will win while the other stays disabled. Also there will be instances when both disable. When a Talon SRX is disabled it will blink orange each LED in an alternate pattern (think rail road crossing). See Talon User Guide for LED table.

Wenry_Hill 04-02-2015 20:32

Re: Talon SRX spamming forward and backward constantly
 
So it turned out that we only disabled half of our encoders. We had old code running the encoders even though we bypassed the joystick inputs. Whenever we tried to move our motors the old code kicked in and tried to bring the wheels back to 0, but overshot and just continued to do so. Thanks everyone for all the help! So mandrews281 make sure you have all your PID loops disabled.

mandrews281 06-02-2015 19:05

Re: Talon SRX spamming forward and backward constantly
 
There are no PIDs in our code. It's only 4 TalonSRX, a robotdrive, a Gyro (disabled I think, need to check with my programming captain) and joystick. I saw 1452-Leo's solution here:

http://www.chiefdelphi.com/forums/sh...5&postcount=20

and I'm thinking that's the way to go. Our electrical team has our test base disassembled at the moment, I'll have to try this tomorrow.

ozrien 07-02-2015 21:17

Re: Talon SRX spamming forward and backward constantly
 
Quote:

We are also seeing some CAN errors from the PDB not responding on the DriverStation messages.
Are you still seeing this? Also, what does that mean exactly?

Is your problem that you are seeing motor safety errors in the DS AND as a result your motors are neutral (solid orange)? Please be specific.


All times are GMT -5. The time now is 21:10.

Powered by vBulletin® Version 3.6.4
Copyright ©2000 - 2017, Jelsoft Enterprises Ltd.
Copyright © Chief Delphi