I recently bought the Miss Geico 36" in order to make an autonomous boat. I’ve set up everything, but I can’t manage to get both Skid Steering and Ground Steering with the rudder.
When I try the rudder by itself with only Servo 3 on Ground Steering, it works.
When I try the skid steering by itself with Servo 1 and 2 on Throttle Right and Left, it works.
When I put all the 3 Servo Outputs, it doesn’t work and I get the following error:
“PreArm: check steering and throttle config”
Is it possible to achieve what I’m trying to do?
Thanks for any help you might provide!
If I remember correctly, the config check looks for valid config pairs: throttle left, throttle right and ground steering, throttle.
If one is missing there will be an error message. So simply configure an output as “throttle” and do not use it.
I don’t think the firmware will accept a dual steering configuration like that as valid. If it were my boat, I’d configure skid steering and then use a Lua script to control the rudder by calculating the difference between the left and right throttle outputs.
Since Miss Gieco is a racing tunnel, I’d forgo the skid steering. Consider a “Y” servo cable and feed both ESCs throttle info and use the rudder servo. Good luck!
That must be a newer sanity check. I remember running such a configuration in the past, but I do not remember with which firmware version. I now use a LUA script to control the active castor wheel on my rover.
I do this on my boat, skid steer + two rudders using the ground steering for rudders and left/right esc. Works for me, I think I have all arming checks off though. I don’t recall any messages like you’re seeing. I can attach the parameters if you want to see?
As others say, AP doesn’t officially support both skid-steering and ackermann steering on the same vehicle (issue is here). The underlying difficulty is that ackermann steering must be scaled by the vehicles speed (the rudder response grows as the vehicle speeds up) while skid-steering is not scaled.
Looking at the code though I think we may have accidentally resolved the problem because the scaling is applied independently within the ackermann output method and that’s a local variable so it shouldn’t affect the skid steering.
… so my guess is that we can actually remove that arming check and it will work (but we need to test in the simulator to be sure).
Turning off all arming checks is generally a bad idea because it will hide other problems but that might be your only option for now (assuming you want both to work).
It crossed my mind that scripted rudder output should be scaled with speed, but I thought perhaps that might happen naturally when the skid steering outputs are adjusted via the rate controller. Might be interesting to remove the arming check (in firmware) and give it a go via parameter setup, though!
There are some other strange issues that can come up when using some steering modes. mode 3 causes the rudder to work against the motors in reverse since right on the the motor control is always clockwise rotation but the rudder changes its direction of rotation depending on if its going forwards or backwards.
The way i was going to solve the problem of mixing different control types was having a different tune for each and then change the parameters with lua when i change control type.
so when cruising my boat will have both motors set to throttle with rudder so no skid steering so it can continue even with a motor failure and it wont try and steer the boat with the motors when sailing. but when I set the switch to mode 2 it will change the motors to left throttle and right throttle, disable the rudder and change the tune to match the new turn rates, then mode 3 will be my thrusters with main motors disabled. essentially letting me switch between skid-steering and ackerman and omni motors on the fly.
something simple like this might work for you, it essentially just temporarily changes the 2 motors and rudder between Ackermann and skid steer using a switch but you could modify it to switch based on other inputs like mode or speed.
local SCRIPT_NAME = 'group motor control.lua'
local RUN_INTERVAL_MS = 200
local RC_OPTION = 300
local THROTTLE =70
local THROTTLE_LEFT =73
local THROTTLE_RIGHT =74
local STEERING =26
local OFF =135
local MAV_SEVERITY_INFO = 6
-- wrapper for gcs:send_text()
local function gcs_msg(severity, txt)
gcs:send_text(severity, string.format('%s: %s', SCRIPT_NAME, txt))
end
-- ! setup/initialization logic
local rc_chan = rc:find_channel_for_option(RC_OPTION)
local last_sw_pos = nil
function update()
local sw_pos = rc_chan:get_aux_switch_pos() -- returns 0, 1, or 2
if sw_pos == last_sw_pos then return update, RUN_INTERVAL_MS end
if sw_pos == 0 then
param:set('SERVO1_FUNCTION', THROTTLE)
param:set('SERVO2_FUNCTION', THROTTLE)
param:set('SERVO3_FUNCTION', STEERING)
)
gcs_msg(MAV_SEVERITY_INFO, 'Ackermann ')
else
param:set('SERVO1_FUNCTION', THROTTLE_LEFT)
param:set('SERVO2_FUNCTION', THROTTLE_RIGHT)
param:set('SERVO3_FUNCTION', OFF)
gcs_msg(MAV_SEVERITY_INFO, 'skid-steering')
end
last_sw_pos = sw_pos
return update, RUN_INTERVAL_MS
end
gcs_msg(MAV_SEVERITY_INFO, 'Initialized.')
return update()
Here is my parameter file. I can’t argue with the caveats people have mentioned here: the reversed reverse issue, and the need for gain scaling with speed. For my boat, which isn’t super fast, I think this works fine. I don’t normally reverse except in manual (I suppose loiter also, I’ll have to watch that next time I’m out). I used the rudders because they were already installed (I joined 2 monohull boats into a catamaran) and because someone once mentioned that if a prop comes out of the water running down a wave you lose steering if you rely on skid steering exclusively. I’m enjoying the discussion!
I’ve never heard of this “reversing issue” so I wonder if someone could explain it to me. My guess is the reversing problem appears on frames like @meholden’s (see above) where there are two rudders, each directly behind a motor. When turning at low speed one motor may spin in reverse and pull water through one of the rudders in the opposite direction to the way the boat overall is moving and so the rudder is essentially pointing in the wrong direction? I guess to work correctly the rudders would need to move independently?
If this is the issue then the “Miss Geico” (pic below) might be unaffected because the rudder and motors are separated.
I have only ever seen it in steering mode 3 where there is a conflict between the direction the rudder is trying to rotate the boat and the direction the motors are trying to rotate the boat but only when reversing.