kauailabs / allwpilib

Fork of Official Repository of WPILibJ and WPILibC, which contain in addition a HAL for the KauaiLabs VMX-pi.
Other
1 stars 3 forks source link

Attempt to close() servo motor throws exception in VMXPI.cpp (Resource routing incomplete) #24

Closed cpeppler01 closed 4 years ago

cpeppler01 commented 4 years ago

Environment: Raspberry Pi v3B. VMX-pi model 0x32, hardware rev 60, firmware version 3.0.411 

Overview: Attempting to control a Feetech (FiTec) Servo Motor, Model FS90MR. Physically connected to High Current DIO port 12, wpilib channel 0

Have had some luck, but trying to gain smooth control over the servo using wpilib Servo class, by using a basic joystick control (Y axis, Joystick 0).

Starting to work with teleopInit() to initialize the servo, and disabledInit() to stop the servo close the motor, and release the Servo object.

There is a repeatable exception thrown by VMXPI.cpp when calling close() on the allocated servo.

Here is relevant log info. Source code to Robot.java is attached.

Internal issue with print and error tags
 VMX HAL:  SPI Aux Channel 2 opened with baudrate of 4000000. 
 VMX HAL:  Established communication with VMX-pi model 0x32, hardware rev 60, firmware version 3.0.411 
 VMX HAL:  Acquired navX-Sensor configuration. 
 VMX HAL:  Library version 1.1.215 
 Set VMX CAN Mode to NORMAL. 
 Server Running... 
 ********** Robot program starting ********** 
 Finished robotInit() 
 Default disabledInit() method... Override me! 
 in overridden disabledInit() 
 disabledInit FS90MR no action. 
 Default disabledPeriodic() method... Override me! 
 Default robotPeriodic() method... Override me! 
 NT: server: client CONNECTED: 10.78.22.18 port 54669 
 Default teleopInit() method... Override me! 
 Watchdog not fed within 0.020000s 
 Created servo objects, Finished teleopInit() 
Warning  1  Loop time of 0.02s overrun
  edu.wpi.first.wpilibj.IterativeRobotBase.printLoopOverrunMessage(IterativeRobotBase.java:273) 
 Warning at edu.wpi.first.wpilibj.IterativeRobotBase.printLoopOverrunMessage(IterativeRobotBase.java:273): Loop time of 0.02s overrun 
  
  teleopPeriodic(): 0.003410s 
  robotPeriodic(): 0.000031s 
  teleopInit(): 0.085643s 
 Default disabledInit() method... Override me! 
 in overridden disabledInit() 
 Attempting to FS90MR.stopMotor() ... 
 ...Successful. Attempting to FS90MR.close() motor ... 
 Tue Apr 21 16:09:48 2020 - WARN :  Error deactivating Resource type 2, index 6 
  (VMXIO.cpp [1215]) 
 Tue Apr 21 16:09:48 2020 - WARN :  Error Code -20011 (Resource routing incomplete) 
  (VMXIO.cpp [1217]) 
ERROR  1  Unhandled exception: edu.wpi.first.hal.util.UncleanStatusException:  Code: -20011. Resource routing incomplete  frc.robot.Robot.disabledInit(Robot.java:51) 
 Error at frc.robot.Robot.disabledInit(Robot.java:51): Unhandled exception: edu.wpi.first.hal.util.UncleanStatusException:  Code: -20011. Resource routing incomplete 
  at edu.wpi.first.hal.PWMJNI.freePWMPort(Native Method) 
  at edu.wpi.first.wpilibj.PWM.close(PWM.java:86) 
  at frc.robot.Robot.disabledInit(Robot.java:51) 
  at edu.wpi.first.wpilibj.IterativeRobotBase.loopFunc(IterativeRobotBase.java:206) 
  at edu.wpi.first.wpilibj.TimedRobot.startCompetition(TimedRobot.java:81) 
  at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:263) 
  at frc.robot.Main.main(Main.java:27) 
  
Warning  1  Robots should not quit, but yours did!  edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:274) 
 Warning at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:274): Robots should not quit, but yours did! 
ERROR  1  The startCompetition() method (or methods called by it) should have handled the exception above.  edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:276) 
 Error at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:276): The startCompetition() method (or methods called by it) should have handled the exception above. 
 # 
 # A fatal error has been detected by the Java Runtime Environment: 
 # 
 #  SIGSEGV (0xb) at pc=0x647fbfd8, pid=1181, tid=1231 
 # 
 # JRE version: OpenJDK Runtime Environment (11.0.6+10) (build 11.0.6+10-post-Raspbian-1deb10u1) 
 # Java VM: OpenJDK Server VM (11.0.6+10-post-Raspbian-1deb10u1, mixed mode, serial gc, linux-) 
 # Problematic frame: 
 # C  [libvmxpi_hal_cpp.so+0xa3fd8][thread 1238 also had an error] 
 [thread 1255 also had an error] 
   spiGoA+0x348 
 # 
 # No core dump will be written. Core dumps have been disabled. To enable core dumping, try "ulimit -c unlimited" before starting Java again 
 # 
 # An error report file with more information is saved as: 
 # //hs_err_pid1181.log 
Warning  44004  FRC:  The Driver Station has lost communication with the robot.  Driver Station 
Warning  44002  Ping Results:  link-bad,  DS radio(.4)-bad,  robot radio(.1)-bad,  roboRIO(.2)-GOOD,  FMS-bad FRC:  Driver Station ping status has changed.  Driver Station 
Warning  44000  DS Disable  Driver Station 
Warning  44000  DS Disable  Driver Station 
Warning  44000  DS Disable  Driver Station 
Warning  44000  DS Disable  Driver Station 
Warning  44000  DS Disable  Driver Station 

Here is the code:

/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
/* Open Source Software - may be modified and shared by FRC teams. The code   */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project.                                                               */
/*----------------------------------------------------------------------------*/

package frc.robot;

import edu.wpi.first.wpilibj.Joystick;
//import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.wpilibj.Servo;
//import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;

/**
 * This sample program shows how to control a motor using a joystick. In the
 * operator control part of the program, the joystick is read and the value is
 * written to the motor.
 *
 * <p>Joystick analog values range from -1 to 1 and speed controller inputs also
 * range from -1 to 1 making it easy to work together.
 */
public class Robot extends TimedRobot {
  //private static final int kMotorPort = 0;
  private static final int kServoPort_FS90MR = 0;
  private static final int kServoPort_SG90 = 1;
  private static final int kJoystickPort = 0;

  //private SpeedController m_motor;
  private Servo m_motor_FS90MR;
  private Servo m_motor_SG90;
  private Joystick m_joystick;

  @Override
  public void robotInit() {
    //m_motor = new PWMVictorSPX(kMotorPort);
    m_joystick = new Joystick(kJoystickPort);
    System.out.println("Finished robotInit()");

  }
@Override
public void disabledInit() {
  super.disabledInit();
  System.out.println("in overridden disabledInit()");
  if (m_motor_FS90MR != null)
  {
    System.out.println("Attempting to FS90MR.stopMotor() ...");
    m_motor_FS90MR.stopMotor();
    System.out.println("...Successful. Attempting to FS90MR.close() motor ...");
    m_motor_FS90MR.close();
    System.out.println("...Successful. Attempting to release motor object ...");
    m_motor_FS90MR = null;
    System.out.println("...Successful. disabledInit stopped and released FS90MR");
  }
  else
  {
    System.out.println("disabledInit FS90MR no action.");
  }
}

  @Override
  public void teleopInit() {
    super.teleopInit();
    m_motor_FS90MR = new Servo(kServoPort_FS90MR);
    double max = 1.5;
    double deadbandMax = 1.3;
    double center = 1.3;
    double deadbandMin = 1.3;
    double min = 1.1;
    m_motor_FS90MR.setBounds(max, deadbandMax, center, deadbandMin, min);

    //m_motor_SG90 = new Servo(kServoPort_SG90);
    //m_motor_SG90.setBounds(2.0, 1.35, 1.2, 1.05, .9);

    System.out.println("Created servo objects, Finished teleopInit()");

  }

  @Override
  public void teleopPeriodic() {
    double rawJoystickValue = m_joystick.getY();
    double joystickValue = Math.abs((rawJoystickValue+1.0)/2.0); 

    //System.out.println("Y value:" + joystickValue);
    m_motor_FS90MR.set(joystickValue);
    //m_motor_SG90.set(m_joystick.getY());
    //m_motor.set(m_joystick.getY());
  }
}
kauailabs commented 4 years ago

Thanks for reporting this.

Root cause analysis: Scope: occurs only in Java (due to WPI Library JNI Layer throwing unhandled exceptions upon "unclean status" codes returned from underlying HAL. Trigger: The unclean status exception happens only for PWM resources when they are closed, due to an overaggressive error check in the underlying VMXpi Platform Library (vmxpi-hal) when a resource is deactivated without have any channels allocated to it. This case occurs in the VMX-pi wpilib hal (for PWM channels only) as it always unroutes PWM channels from PWM generator resources, and then only deallocates the PWM Generator resource once the number of routed channels drops to 0. This logic is in place to handle cases (e.g., FlexDIO PWM Generator Channels) which can route multiple channels per PWM Generator Resource.

The fix for this issue will be in the VMX-pi Platform Library (vmxpi-hal). This github issue will be closed once that release has ocurred.

This case is not exercised typically (robot applications typically don't close/release the resources they allocate). Until fixed, the recommended workaround is to either not close the PWM resource, or to add an exception handler around the code that invokes it.

We can only hope that the WPI Library will fix the policy of allowing unhandled exceptions to occur when unclean status codes are returned from the HAL, but we don't have control over that part.

kauailabs commented 4 years ago

This issue is resolved by an updated version of the Kauai Labs vmxpi-hal library for the Raspberry Pi (v. 1.1.220).

To install this updated library on your raspberry pi, after ensuring the raspberry pi is connected to the internet, from a console terminal run the following commands:

sudo apt-get update sudo apt-get install vmxpi-hal

If the installation does not work as expected, you may need to run these commands in order: sudo apt-get remove vmxpi-hal sudo apt-get install vmxpi-hal