Reactivate auto steer switch after current limit

Hi! :slight_smile:
I am using a switch combined with my hydraulic hight to activate/deactivate auto steer. I want to include the current limit function to switch of the auto steer in case of trying to move steering wheel manually against the motor. It works but if the current is back in range the auto steer is immediately active again. This is not good in some cases. Wouldn’t it be better to reactivate it manually by switching it off/on or push the auto steer button in the software in this case?
If you use a hardware button instead of the switch it works but in combination with the hydraulic hight I have to use the switch function.
Or is there a way I don’t know?

Best regards
Christoph

You use hydraulic raise lower switch as autosteer switch? If so using it as a button in AOG you have to click it again to restart autosteer that would raise your impliment. As there are impliments that don’t require hidraulics lift and problems with reengagement of autosteer that way. Why not just have normal separate button / switch for engaging autosteer something like foot switch?

I have to explain a bit more.
So far i dont use the relays for automatic move up and down the hydraulic.

I have an outputsignal in my tractors iso-socket which gives me 12V when the hydraulic is in Up-position and 0V in Down-position/working-position. With this signal i switch on/off the autosteer by using a relaise which acts like a switch. It works really good and i dont have to push a button or switch everytime i turn.
The reason why i dont use a button is i also switch off the Power to the motor. The cytron is blocking the motor to much if i dont disconnect the motor from the cytron driver and its not nice to disengage the motor from the steering wheel physically everytime.
Thats why i was thinking about this option which is not complicated to implement i think and you can use switch and button with the overcurrent function.

No need for physical disconnect with this cytron mod.

1 Like

I understand that you use iso 11786 connector to engage the autosteer according the position of linkage pin 5 (and 7 for ground)

it is hope to you but in this case you are in swich mode

and switch mode and overcurrent function is not the best

after arduino code is open and you can modify as you want …

To my experiance i have opposite view

  • Tractor control can be use as manual mode
  • AOG control can operate tractor control to be automated

and

  • tractor control can activate very low level like color maping … ( with ISO 11786 connector as you say )
  • function like Autosteer need to be clearly decided by operator to activate

To be desactivated extra thing like overcurrent or over pressure can do it …

Here is some code that might help. It stays off after an overcurrent. It adds the boolean Latched to do this. You will also have to declare the variables bool Latched and int8_t SWpin.

   void loop()
  {
    // Loop triggers every 100 msec and sends back gyro heading, and roll, steer angle etc   
    currentTime = millis();
   
    if (currentTime - lastTime >= LOOP_TIME)
    {
      lastTime = currentTime;
  
      //reset debounce
      encEnable = true;
      
      //If connection lost to AgOpenGPS, the watchdog will count up and turn off steering
      if (watchdogTimer++ > 250) watchdogTimer = WATCHDOG_FORCE_VALUE;
      
     //read all the switches
      workSwitch = digitalRead(WORKSW_PIN);  // read work switch
      
      if (steerConfig.SteerSwitch == 1)         //steer switch on - off
      {
          SWpin = digitalRead(STEERSW_PIN); //read auto steer enable switch open = 0n closed = Off
          if (SWpin == LOW && !Latched) steerSwitch = SWpin;
          if (SWpin)
          {
              Latched = false;
              SteerSwitch = SWpin;
          }
      }
      else if(steerConfig.SteerButton == 1)     //steer Button momentary
      {
        reading = digitalRead(STEERSW_PIN);      
        if (reading == LOW && previous == HIGH) 
        {
          if (currentState == 1)
          {
            currentState = 0;
            steerSwitch = 0;
          }
          else
          {
            currentState = 1;
            steerSwitch = 1;
          }
        }      
        previous = reading;
      }
      else                                      // No steer switch and no steer button
      {
        // So set the correct value. When guidanceStatus = 1, 
        // it should be on because the button is pressed in the GUI
        // But the guidancestatus should have set it off first
          if (guidanceStatusChanged && guidanceStatus == 1 && steerSwitch == 1 && previous == 0)
          {
              steerSwitch = 0;
              previous = 1;
          }

          // This will set steerswitch off and make the above check wait until the guidanceStatus has gone to 0
          if (guidanceStatusChanged && guidanceStatus == 0 && steerSwitch == 0 && previous == 1)
          {
              steerSwitch = 1;
              previous = 0;
          }
      }

      if (steerConfig.ShaftEncoder && pulseCount >= steerConfig.PulseCountMax) 
      {
        steerSwitch = 1; // reset values like it turned off
        currentState = 1;
        previous = 0;
        Latched = true;
      }

      // Pressure sensor?
      if (steerConfig.PressureSensor)
      {
          sensorSample = (float)analogRead(ANALOG_SENSOR_PIN);
          sensorSample *= 0.25;
          sensorReading = sensorReading * 0.6 + sensorSample * 0.4;
          if (sensorReading >= steerConfig.PulseCountMax)
          {
              steerSwitch = 1; // reset values like it turned off
              currentState = 1;
              previous = 0;
              Latched = true;
          }
      }

1 Like

Thanks a lot for your code! I was thinking about to do it myself but my coding knowledge is not the best…

I will try it next days!

Meanwhile i tested the code and changed it a bit but now it works how it should.
Thanks again for help!

best regards!

void loop()
  {
    // Loop triggers every 100 msec and sends back gyro heading, and roll, steer angle etc   
    currentTime = millis();
   
    if (currentTime - lastTime >= LOOP_TIME)
    {
      lastTime = currentTime;
  
      //reset debounce
      encEnable = true;
      
      //If connection lost to AgOpenGPS, the watchdog will count up and turn off steering
      if (watchdogTimer++ > 250) watchdogTimer = WATCHDOG_FORCE_VALUE;
      
     //read all the switches
      workSwitch = digitalRead(WORKSW_PIN);  // read work switch
      
      if (steerConfig.SteerSwitch == 1)         //steer switch on - off
      {
          SWpin = digitalRead(STEERSW_PIN); //read auto steer enable switch open = 0n closed = Off
            if (SWpin == LOW && !Latched) 
            {
              steerSwitch = SWpin;
            }
            else
            {
              steerSwitch = HIGH;
            }
          
            if (SWpin == HIGH) 
            {
              steerSwitch = SWpin;
              Latched = false;
            }
          
      }
      else if(steerConfig.SteerButton == 1)     //steer Button momentary
      {
        reading = digitalRead(STEERSW_PIN);      
        if (reading == LOW && previous == HIGH) 
        {
          if (currentState == 1)
          {
            currentState = 0;
            steerSwitch = 0;
          }
          else
          {
            currentState = 1;
            steerSwitch = 1;
          }
        }      
        previous = reading;
      }
      else                                      // No steer switch and no steer button
      {
        // So set the correct value. When guidanceStatus = 1, 
        // it should be on because the button is pressed in the GUI
        // But the guidancestatus should have set it off first
          if (guidanceStatusChanged && guidanceStatus == 1 && steerSwitch == 1 && previous == 0)
          {
              steerSwitch = 0;
              previous = 1;
          }

          // This will set steerswitch off and make the above check wait until the guidanceStatus has gone to 0
          if (guidanceStatusChanged && guidanceStatus == 0 && steerSwitch == 0 && previous == 1)
          {
              steerSwitch = 1;
              previous = 0;
          }
      }

      if (steerConfig.ShaftEncoder && pulseCount >= steerConfig.PulseCountMax) 
      {
        steerSwitch = 1; // reset values like it turned off
        currentState = 1;
        previous = 0;
        Latched = true;
      }

      // Pressure sensor?
      if (steerConfig.PressureSensor)
      {
          sensorSample = (float)analogRead(ANALOG_SENSOR_PIN);
          sensorSample *= 0.25;
          sensorReading = sensorReading * 0.6 + sensorSample * 0.4;
          if (sensorReading >= steerConfig.PulseCountMax)
          {
              steerSwitch = 1; // reset values like it turned off
              currentState = 1;
              previous = 0;
              Latched = true;
          }
      }

      //Current sensor?
      if (steerConfig.CurrentSensor)
      {
          sensorSample = (float)analogRead(ANALOG_SENSOR_PIN);
          sensorSample = (abs(512 - sensorSample)) * 0.5;
          sensorReading = sensorReading * 0.7 + sensorSample * 0.3;
          if (sensorReading >= steerConfig.PulseCountMax)
          {
              steerSwitch = 1; // reset values like it turned off
              currentState = 1;
              previous = 0;
              Latched = true;
          }
      }