To switch into Loiter you’ll probably need to set one of the MODEx parameters to “5”. Once Rover-3.4 becomes the official release then the mode will appear in the flight mode setup screen in Mission Planner (and other GCSs). I’ve added a note to the Loiter mode wiki page as well.
Re acro improvements, I’m guessing but it could be the reversing control improvements. If ATC_BRAKE was set to 1 and the speed controller momentarily set the throttle output to reverse (in order to slow down the vehicle) the skid-steering vehicles could suddenly turn the wrong way.
You check if _throttle_decel_max is positive before applying it, but not _throttle_accel_max. If _throttle_accel_max is set to 0, then the vehicle never accelerates, whereas the parameter notes say that 0 should give unlimited acceleration.
Also, if throttle_decel_max is zero, then you become limited by your ACCELERATION max.
This would be my suggestion (noting I don’t understand the role of the abs on the speeds):
Also, did you say you’d fixed the sudden deceleration at each waypoint? If you set up a very high deceleration rate and a low acceleration rate you can still see the vehicle slow down dramatically every time it passes a waypoint.
With more sensible values, it hides the deceleration (e.g. decel of 10).
Yes, we’ve mostly fixed the sudden deceleration after passing waypoints. There are still two situations where it accelerates or decelerates too quickly:
if the vehicle is put into Auto mode while disarmed and then armed, the desired speed will immediately jump to the CRUISE_SPEED/WP_SPEED. The work around for this issue is to arm in another mode and then switch to Auto.
at the end of a mission (when vehicle reaches the WP_RADIUS around the final waypoint), the vehicle switches into Hold mode and the throttle output is immediately set to zero. The vehicle will likely have slowed before reaching the waypoint but the vehicle will still likely come to a slightly sudden stop.
Both these issues are captured in this issue so I’m pretty sure we will fix them in a follow-up release. These issues are not new though.
Ah, thanks for the note on finding the code issue re the accel/decel. I’ll have a look at it or perhaps @Ammarf will.
I’m comparing sim performance between 3.3 and 3.4. I find that 3.4 makes MUCH wider turns than 3.3. Running both at 1.0m/s gives the same performance, but where 3.3 followed the same path at increasing speed until you hit turn_max_g, 3.4 seems to increase the turn radius as you increase speed.
Is it possible to upload logs here?
I’ve increased the turn radius in SIM_Rover.cpp to 5m (otherwise it’s very hard to replicate due to minimum speeds). This is for a conventional steering rover - have the other people in the thread been running skid steer?
The biggest change in the code I can see is the removal of the 1/speed scale factor in AR_attitudeControl, but that seems like removing that should INCREASE the steering input, and make it turn tighter (comparatively) as speed increases - you’re no longer dividing the error by 5 for example.
Great video. I think it’s quite clear when the vehicle is switches into Loiter that it initially drifts and then it behaves like it’s front is caught on a string (which is how it should act). Thanks!
Re the omnirover, I think we will add a page to the Reference Frames section of the wiki and also add a section to the Motor and Servo wiki page but I’m afraid for now all I have is a picture. There’s only one motor configuration supported at the moment which is three wheels positions at 120degree increments around the frame. the SERVOx_FUNCTION values for the three outputs should be set to motor1 (33), motor2 (34) and motor3 (35) respectively.
Greetings. Very good development of beta tests v3.4.0 rc1. An incredible video clip. I have a question: I want to use the Loiter mode for an inflatable fishing boat with a 3,3 m long. I’m using a 30 lbs DC submersible motor. I’ve also set up a preset model. There is no good test of orientation of the model to a given point on a mission. The servo 1 is 360 deg and has a gear with i = 2,5. Is this configuration of mechanics appropriate? Do I have to set additional parameters?
@rmackay9, I’ve been digging into the changes to AR_AttitudeControl and AP_MotorsUGV and I’ve found something that makes me go “hmmm”.
3.3: AR_AttitudeControl applies a 1/speed scaling factor in calculation of the steering output through the PID, then constrains the result to +/-1.0 before returning it. That steering is then sent out unchanged in AP_MotorsUGV.cpp
3.4: You remove the 1/speed scale factor in AR_AttitudeControl (so the calculated values will be a lot larger), but you still constrain it to +/1 before returning it.
This (I think) explains some of the funky behaviour I’ve been seeing where servo output is clipped at high speeds in Acro mode. If my servo range is 1000-1500-2000, the most steering I can get at 10m/s is 1450 or 1550. Set up 3.4 with a high turn_max_g (like 7), a high FF (2), and speed_turn_gain of 100%, then run your kart track at 10m/s. It will go nuts, but if you watch the ch1out, once it’s at speed it will never go outside of 1450-1550.
The same thing in 3.3 will show a greater range of steering output.
I think the fix is removing the “constrain” at the end of get_steering_out_rate, and from “set_steering” in AP_MotorsUGV to leave the clipping to the final output.
The alternative would be to do the speed correction / scaling in mode.cpp (calc_steering_from_lateral_acceleration) since that’s where you have a direct link between the steering and the velocity, just before it gets sent to g2.motors.set_steering(). There’s almost no need for the motor to manage that side of things. (IMHO).
It wont show up at low speeds if your required steering is less than 1/speed % - i.e. if you need less than 20% steering at 5m/s it wont clip.
I totally agree. Actually I hit this issue yesterday on my high speed boat. I just could not get it to turn quickly at high speed even though it would turn on a dime in manual mode.
When I made the change you’ve found, I recognised that this could be an issue (it’s mentioned in the PR but that reaches a limited audience) but hoped that we could get away with it. I might work on this today.
I guess you would vote for us holding off on Rover-3.4 release until we fix this? I’m keen to release 3.4 but lose of steering control on high speed vehicles is a serious issue so I think we probably have to fix it first, then release -rc2, test that and then finally release 3.4 officially.
Given that the lane following looks close to being done, could you incorporate that into 3.4-rc2 with a flag to turn it off - it’s not entirely clear from the lane following how to disable it.
Re your fix, it doesn’t look like you’ve removed the +/-1.0 constraint at the end of AR_AttitudeControl - that’s the critical one.