|
|
|
![]() |
|
|||||||
|
||||||||
![]() |
|
|
Thread Tools | Rate Thread | Display Modes |
|
|
|
#1
|
|||
|
|||
|
CAN Talon not working after disabling robot and re-enabling
We decided to switch from PWM Talon to CAN Talon SRX to try and take advantage of the integrated closed loop capabilities
Out first test was to use the CAN Talon's straight out of robot builder as part of a dual motor controller drive train. All the code works correctly except that when we disable the robot then re-enable in tele-op, the motors don't move (and the LEDs on the CAN Talon's) don't change colors red/green - they just blink yellow) Restarting robot code solves the problem. We switch back to PWM talons and all works correctly. We are suspecting something happens to the motor controllers when we disable. The CAN Talon SRX manual makes note of needing to service the controllers during disable_periodic. Curious if anyone else has this issue. |
|
#2
|
|||
|
|||
|
We are having a similar problem, and will be wiring up the talons with pwm tonight
|
|
#3
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
I was reading the Talon software manuals last night and I'm planning on checking the status of the Talons on the Roborio web page to see if they are disabled. We did confirm with the debugger that we are correctly calling the robotdrive "drive" functions with a valid magnitude and curve, so it feels like the CAN Talon is disabled...
|
|
#4
|
||||
|
||||
|
Re: CAN Talon not working after disabling robot and re-enabling
Is the Talon firmware up-to-date?
Any errors in the DS message view? Post your code? |
|
#5
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
teleop periodic:
Code:
void Robot::TeleopPeriodic() {
Scheduler::GetInstance()->Run();
Robot::drivetrain->robotDrive->ArcadeDrive(Robot::oi->driveStick
->GetX(),Robot::oi->driveStick->GetRawAxis(4));
}
Code:
// BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=ALLOCATION
std::shared_ptr<CANTalon> RobotMap::drivetraindriveSRX1;
std::shared_ptr<CANTalon> RobotMap::drivetraindriveSRX2;
std::shared_ptr<CANTalon> RobotMap::drivetraindriveSRX3;
std::shared_ptr<CANTalon> RobotMap::drivetraindriveSRX4;
std::shared_ptr<RobotDrive> RobotMap::drivetrainRobotDrive;
// END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=ALLOCATION
void RobotMap::init() {
// BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
LiveWindow *lw = LiveWindow::GetInstance();
drivetraindriveSRX1.reset(new CANTalon(0));
lw->AddActuator("Drivetrain", "driveSRX1", drivetraindriveSRX1);
drivetraindriveSRX2.reset(new CANTalon(1));
lw->AddActuator("Drivetrain", "driveSRX2", drivetraindriveSRX2);
drivetraindriveSRX3.reset(new CANTalon(2));
lw->AddActuator("Drivetrain", "driveSRX3", drivetraindriveSRX3);
drivetraindriveSRX4.reset(new CANTalon(3));
lw->AddActuator("Drivetrain", "driveSRX4", drivetraindriveSRX4);
drivetrainRobotDrive.reset(new RobotDrive(drivetraindriveSRX1, drivetraindriveSRX2,
drivetraindriveSRX3, drivetraindriveSRX4));
drivetrainRobotDrive->SetSafetyEnabled(true);
drivetrainRobotDrive->SetExpiration(0.1);
drivetrainRobotDrive->SetSensitivity(0.5);
drivetrainRobotDrive->SetMaxOutput(1.0);
drivetrainRobotDrive->SetInvertedMotor(RobotDrive::kFrontLeftMotor, true);
drivetrainRobotDrive->SetInvertedMotor(RobotDrive::kRearLeftMotor, true);
drivetrainRobotDrive->SetInvertedMotor(RobotDrive::kFrontRightMotor, true);
drivetrainRobotDrive->SetInvertedMotor(RobotDrive::kRearRightMotor, true);
// END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
}
Last edited by snekiam : 02-02-2016 at 03:15 PM. Reason: accidental partial submission at first |
|
#6
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
Looking at the self test results of the CAN Talon SRX in Roborio web page:
When our code works, the Talon's report Enabled/Mode 0 We then disable and re-enable in teleop mode and the Talon's report "Enabled/Mode 15" It seems like the CAN Talons switch to mode 15 when we disable. We tried setting the modes back to 0 in the teleop init, but it doesn't seem to force them to change mode (Roborio still reports them as Mode 15) Continuing to read Talon SRX Software User's Guide for hints.. |
|
#7
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
Quote:
|
|
#8
|
||||
|
||||
|
Re: CAN Talon not working after disabling robot and re-enabling
So the Self-Test is displaying "Mode: 15 : No Drive".
Can you try section 16.12 in the Talon SRX Software Reference Manual. |
|
#9
|
||||
|
||||
|
Re: CAN Talon not working after disabling robot and re-enabling
Looking at WPILIB c++, RobotDrive appears to call Disable() when RobotDrive::StopMotor() is called. But it doesn't Enable() anywhere. Are you calling StopMotor()? If so try setting the output to zero using the normal routine instead (arcadeDrive, tankDrive, etc.).
|
|
#10
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
We are calling stopmotor() at then end of our autonomous. I realized this last night and had theorized something like you discovered in the WPIlib source..
|
|
#11
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
Yes, this was the first thing we tried last night once we discovered Mode 15. It appears to give us consistent operation toggling enable/disable in Teleop. We still have an issue going between autonomous and teleop, but I believe this 16.12 workaround is certainly poking at the problem area..
|
|
#12
|
|||
|
|||
|
Re: CAN Talon not working after disabling robot and re-enabling
Quote:
We now have reliable open loop control of the CAN talons...now on to closed loop! |
|
#13
|
||||
|
||||
|
Re: CAN Talon not working after disabling robot and re-enabling
Several of our CANTalon's had firmware 0.28, and after we updated them to 2.0 everything started working as intended.
Not sure if this is your problem, but a nice update can never hurt. |
![]() |
| Thread Tools | |
| Display Modes | Rate This Thread |
|
|