Safety flashlight on Rover

Hello,

I have created a 120 kg rover and would like to install a safety flashlight, which lights up when the rover moves forward, whether in manual or automatic mode.
I only need the light to work when the rover is moving, because in automatic mode I expect it to take long breaks during these GPS runs.

It is a Skid steering rover equipped with an Orange Cube and a MAUCH power module.

I have thought about several systems such as:
install a sensor on a wheel shaft
measure the current at the level of the motor to trigger the system, etc …

But in the end, it doesn’t quite suit me.

I wanted to know if I could drive a relay through the Cube. For example, as soon as the throttle’s PWM is not at neutral, I activate the relay.

Or, connect a microcontroller between the Cube and the Cube’s current sensor to drive a relay. For example, if the current is greater than 2A, I operate the lamp.

Could you tell me what you think?

Thank you in advance for your help,

Dorian

Use a relay connected to one of the Aux output pins and control it with a Lua script. The Cube Orange is well suited to run a script like that.

Thanks for this information, I will study this!

To save you a little time/trouble, speed (m/s) can be stored in a variable like this:

local speed = ahrs:groundspeed_vector():length()

Once the AHRS is active/healthy, the vector will almost always be non-zero, so you’ll want to establish a non-zero threshold above which the light relay is activated.

1 Like

Thanks for your help !

The problem in this case is that you need GPS information.
Now, I want the flashlight to work as soon as the rover moves forward, for example, if I take it out of a truck in manual mode, there will be no GPS signal.

I was thinking either:

  • be able to read the accelerator’s PWM while operating as follows:
    if (throtlle_pwm <1490) or (throtlle_pwm> 1510), then activate a relay

  • another less elegant solution by reading the current consumed:
    if (current_read <2 amps), then activate a relay

What do you think ?

I’ll do you one better:

local RELAY          =    2 -- relay to control
local THRESHOLD      = 0.01
local FREQUENCY      =  200 -- (ms)
local THROTTLE_INDEX =    3
local STEERING_INDEX =    4

function throttle_disengaged()
    local throttle = vehicle:get_control_output(THROTTLE_INDEX)
    local steering = vehicle:get_control_output(STEERING_INDEX)
    if math.abs(throttle) + math.abs(steering) >= THRESHOLD then
        relay:on(RELAY)
        gcs:send_text(5, 'Lights: ON')
        return throttle_engaged, FREQUENCY
    end
    return throttle_disengaged, FREQUENCY
end

function throttle_engaged()
    local throttle = vehicle:get_control_output(THROTTLE_INDEX)
    local steering = vehicle:get_control_output(STEERING_INDEX)
    if math.abs(throttle) + math.abs(steering) < THRESHOLD then
        relay:off(RELAY)
        gcs:send_text(5, 'Lights: OFF')
        return throttle_disengaged, FREQUENCY
    end
    return throttle_engaged, FREQUENCY
end

gcs:send_text(6, 'Lights: Script active')

return throttle_disengaged()

I’ve been meaning to look at the vehicle:<control output> methods anyway, so this gave me good reason to see how they work. In this case, the throttle variable is commanded throttle output percentage (0.0 to 1.0).

I think the relays are 0 indexed in Lua, meaning that if you configure relay 3 in the parameters, you’ll reference relay 2 in Lua.

Wow, that’s really super nice !

I will test this this weekend

Thanks again !

1 Like

I did some testing today and it works in both manual and automatic modes !

For information, for those interested in this system, it does not activate in reverse gear and when the rover turns in place with skid steering.

Thank you again for your help !

I almost replied yesterday to mention that it may not work in reverse, but then thought I should do some testing of my own before that. Thank you for testing it before I had the chance!

EDIT:
I edited the code in the post above, and it should now work in reverse and during pivot turns with the addition of math.abs(throttle) + math.abs(steering).

Hello,

I’ve done some tests and it works, it’s great !

1 Like