core icon indicating copy to clipboard operation
core copied to clipboard

troggle stepper enable on reset

Open Tsillen opened this issue 3 years ago • 17 comments

My use case: alarm of IHSV57 servo's are hooked up to my e-stop circuit. In the case of a alarm, e-stop input pulls low. In order to reset this either power cycle servo's (not ideal) or troggle drive enable .

To my suprise this drive enable/disable does not occur when you reset the board. It only occurs if you change a setting (in IO SENDER).

Ideally you would see an option somewhere to troggle enable/disable of stepper/servo's on init/reset.

Tsillen avatar Jun 16 '22 21:06 Tsillen

A plugin can do that by hooking code into hal.driver_reset and registering a function to be called on startup in the plugins init function. Here is an example of the use of those methods.

Toggling the enable signal can be done by calling hal.stepper.enable().

terjeio avatar Jun 17 '22 06:06 terjeio

So if i understand correctly `static void on_driver_reset (void) {

hal.stepper.enable(0xFF);
1 sec delay
hal.stepper.enable(0x00);
driver_reset();

if(power_state != Power_On)
    check_power_restored();

} `

Tsillen avatar Jun 17 '22 07:06 Tsillen

You have to cast the argument to hal.stepper.enable like this: hal.stepper.enable((axes_signals_t){AXES_BITMASK}); and hal.stepper.enable(s(axes_signals_t){0});

1 sec delay is hal.delay_ms(1000, NULL);

terjeio avatar Jun 17 '22 07:06 terjeio

awesome, i'll have a try.

Tsillen avatar Jun 17 '22 07:06 Tsillen

ssr.c (probably don't need half of these includes)

#include "driver.h"

#if SERVO_RESET_ENABLE // Declared in my_machine.h - you must add in the section with the included plugins
#include "grbl/protocol.h"
#include "grbl/hal.h"
#include "grbl/state_machine.h"
#include "grbl/system.h"
#include "grbl/alarms.h"
#include "grbl/nuts_bolts.h"         // For delay_sec non-blocking timer function


// Declarations
static driver_reset_ptr driver_reset;
// DRIVER RESET
static void driverReset (void)
{
    hal.stepper.enable((axes_signals_t){0}); //disable drives
    hal.delay_ms(1000, NULL); // wait a second
    hal.stepper.enable((axes_signals_t){1}); //enable drives
    driver_reset();
}

// INIT FUNCTION - CALLED FROM plugins_init.h()
// void my_plugin_init() {
void ssr_init() 
{

    driver_reset = hal.driver_reset;                    // Subscribe to driver reset event
    hal.driver_reset = driverReset;

    
 }
#endif

plugins_init.h add:

#if SERVO_RESET_ENABLE
    extern void ssr_init (void);
    ssr_init();
#endif

my_machine.h add: #define SERVO_RESET_ENABLE 1

I was kinda suprised that it found my ssr.c as nowhere i let it know it is in the /ssr/ folder but it seems to compile. Now lets see if it works.

Tsillen avatar Jun 17 '22 10:06 Tsillen

yup this works.

When my servo goes in alarm -> pulls e-stop -> pressing reset in iosender now pulls drive enable and clears servo alarm.

Tsillen avatar Jun 17 '22 10:06 Tsillen

Well does something weird. if servo alarm goes off -> pulls e-stop -> i see that there is no alarm light on my servo. When i check the status (over RS232 directly into servo) it shows that drive_enable is low. It seems that it auto triggers and reset which is not the intended goal.

Goal is to reset it when i press the big reset button: image

Seems like hal.driver_reset is auto called when e-stop is active.

Tsillen avatar Jun 17 '22 10:06 Tsillen

Seems like hal.driver_reset is auto called when e-stop is active.

Correct, you'll have to check if e-stop is active and delay action until it is cleared?

if (!hal.control.get_state().e_stop)
    toggle enable

terjeio avatar Jun 17 '22 11:06 terjeio

during e-stop drivers can stay enabled. I should toggle enable after this code is cleared.

Tsillen avatar Jun 17 '22 11:06 Tsillen

#include "driver.h"

#if SERVO_RESET_ENABLE // Declared in my_machine.h - you must add in the section with the included plugins
#include "grbl/protocol.h"
#include "grbl/hal.h"
#include "grbl/state_machine.h"
#include "grbl/system.h"
#include "grbl/alarms.h"
#include "grbl/nuts_bolts.h"         // For delay_sec non-blocking timer function


// Declarations
static driver_reset_ptr driver_reset;
uint8_t holdbit = 0; //holdbit for servo enable toggle
// DRIVER RESET
static void driverReset (void)
{
    if (holdbit == 1)
    {
        hal.stepper.enable((axes_signals_t){0}); //disable drives
        hal.delay_ms(1000, NULL); // wait a second 
        hal.stepper.enable((axes_signals_t){1}); //enable drives
        holdbit = 0; //reset holdbit
    }
    driver_reset();
}

// INIT FUNCTION - CALLED FROM plugins_init.h()
// void my_plugin_init() {
void ssr_init() 
{

    driver_reset = hal.driver_reset;                    // Subscribe to driver reset event
    hal.driver_reset = driverReset;
 }
#endif


if (hal.control.get_state().e_stop) //estop event
{
    holdbit = 1; //set holdbit
}

Tsillen avatar Jun 17 '22 11:06 Tsillen

i think something like this should work. need to check where i can put the estop event code

Tsillen avatar Jun 17 '22 11:06 Tsillen

need to check where i can put the estop event code

It is not an event callback, the hal.control.get_state().e_stop call reads the status directly from the input.

terjeio avatar Jun 17 '22 11:06 terjeio

image Iosender does not allow me to reset while e-stop is active (alarm from servos)

I tried this: but i can't send reset in current state so it is kinda stuck. Not sure how do to this behavoir other than adding extra buttons etc.

#include "driver.h"

#if SERVO_RESET_ENABLE // Declared in my_machine.h - you must add in the section with the included plugins
#include "grbl/protocol.h"
#include "grbl/hal.h"
#include "grbl/state_machine.h"
#include "grbl/system.h"
#include "grbl/alarms.h"
#include "grbl/nuts_bolts.h"         // For delay_sec non-blocking timer function


// Declarations
static driver_reset_ptr driver_reset;
uint8_t holdbit = 0; //holdbit for servo enable toggle

// DRIVER RESET
static void driverReset (void)
{
    if (holdbit == 1) //should i check if e-stop is still high?
    {
        hal.stepper.enable((axes_signals_t){0}); //disable drives
        hal.delay_ms(1000, NULL); // wait a second 
        hal.stepper.enable((axes_signals_t){1}); //enable drives
        holdbit = 0; //reset holdbit
    } 
    else if (hal.control.get_state().e_stop) //if e-stop pin is high
    {
        holdbit = 1; //set holdbit
    }
    
    driver_reset();
}

// INIT FUNCTION - CALLED FROM plugins_init.h()
// void my_plugin_init() {
void ssr_init() 
{

    driver_reset = hal.driver_reset;                    // Subscribe to driver reset event
    hal.driver_reset = driverReset;
}
#endif

Tsillen avatar Jun 17 '22 11:06 Tsillen

If you want to trap the e-stop event you can attach your code to hal.control.interrupt_callback in the same manner as you do for hal.driver_reset. Here is the core handler for the callback:

https://github.com/grblHAL/core/blob/45b0e105892d08e76d5140871cfb032d445d2f20/system.c#L92-L139

terjeio avatar Jun 17 '22 11:06 terjeio

Iosender does not allow me to reset while e-stop is active (alarm from servos)

grblHAL blocks this - the servo alarm should trigger the motor fault signal instead? If the driver you are using has aux inputs you could claim one and use that to trigger the signal.

terjeio avatar Jun 17 '22 12:06 terjeio

Hi i'm using the grblhal2k: https://github.com/Expatria-Technologies/grblhal_2000_PrintNC

I believe it has aux inputs. Will investigate further

Tsillen avatar Jun 17 '22 14:06 Tsillen

Using this code for now, works well enough. https://github.com/grblHAL/core/issues/150#issuecomment-1158735296

At some point i might use the motor fault input.

Tsillen avatar Jun 22 '22 06:06 Tsillen