Hi community!
Iām using a Pixhawk to drive my rover with ackermann steering between predefined waypoints. Throttle and steering are not directly connected to the Pixhawk. Instead the actuator output values will be sent via MAVLink (Message #375) to the body controller of the rover that controls the motors.
Issue: In mission mode the roverās steering oscillates instead of driving directly (in a straight line) to the next waypoint. The rover is much bigger than a normal 1:10 RC rover (GND_WHEEL_BASE = 1,15m; similar to a ATV). In addition the steering is not that responsive as a servo motor in a RC rover. Maybe that is the problem.
I tried changing GND_L1_DAMPING, GND_L1_DIST and GND_L1_PERIOD within the recommended range, but the behaviour is the same. The rover stops oscillating with GND_L1_PERIOD > 200m and GND_L1_DAMPING < 0.3, but then it is not possible to drive any (sharp) curve.
Manual mode is working very well. A full steering command response in a maximum steering angle without any death zone. Therefore GND_MAX_ANG seems to be ok.
Please find the log here: https://logs.px4.io/plot_app?log=8f79fbc7-d104-465a-a27d-e5cfad88f94c
Any idea how to fix this issue?
Weāre currently re-working the akcermann rover guidance, have a look at Rover ackermann module by chfriedrich98 Ā· Pull Request #23024 Ā· PX4/PX4-Autopilot Ā· GitHub
Would be cool if you could try it out and provide feedback!
@sfuhrer: Thank you for the link! I am going to test the module this week.
Just started with cloning the repository and adding the module with āCONFIG_MODULES_ACKERMANN_DRIVE=yā in the default.px4board file of the appropriate board (fmu-v6x in my case).
Unfortunately make px4_fmu-v6x_default fails with the folloing error:
ā¦/ā¦/src/modules/ackermann_drive/AckermannDrive.hpp:104:28: error: āRDD_SPEED_SCALEā is not a member of āpx4::paramsā
104 | (ParamFloatpx4::params::RDD_SPEED_SCALE) _param_rdd_speed_scale,
Are there any dependencies to other modules?
Which airframe do I have to choose for using the module?
Hi,
Is it possible that you cloned the rover_ackermann branch rather than the mentioned PR?
The rover_ackermann branch is an old development branch that does not work in its current state and should probably be deleted to eliminate this confusion.
Let me know if it works if you use the PR!
Good point! Actually I cloned the branch instead of the PR. This time the build was successful after adding the module.
Next issue: the new airframe does not appear in QGC. I already tried make clean. Is there anything else I need to do? I am using QGC v4.0.
The module uses a custom airframe configuration. In QGC try setting the parameter SYS_AUTOSTART to 50010 and reboot the vehicle, this should load everything in. You can then assign your actuator mappings in the Actuators tab.
Module is running! It was my first try to get a build running that is not āout of the boxā. So, sorry for the question and thank your for your help!
I will test your module in the next days on a small 1/10 RC rover and on a much bigger ATV and give you feedback.
Great to hear, happy to help!
Looking forward to get your feedback and feel free to ask if you run into any issues, the module is still WIP.
Hi @Christian_Friedrich, here comes some feedback:
First of all, I will thank you for your work! It is a pleasure to watch the vehicles driving around. No comparison to the rover_pos_control module!
I tested a RC rover (wheelbase = 0,228 m) and an ATV (wheelbase = 1,15 m) on the same mission. Both are working very well. You can find the best plots below.
Rover: https://review.px4.io/plot_app?log=e3c62793-4cf6-490c-ba86-b91e59c450f0
ATV: https://review.px4.io/plot_app?log=914f19bf-48eb-42ac-b0ed-fa9af1a2fda2
Turning: Reducing the speed while turning is a very nice feature. Espacially for big vehicles, it would be better to start reducing the speed before the vehicle starts turning. At the moment, it starts turning at full speed and reduces the speed in the middle of the corner. I know, thatās whining on a high level. The adaptation would allow (bigger) vehicles to drive at a higher speed on the straights, without any risk of falling over in sharp turns.
Steering: When a new waypoint is targeted, the steering is very aggressive. This is probably due to the sudden heading error. It would be cool if there was a parameter that could be used to limit the maximum steering angle change per time unit.
The deflection is far less aggressive (due to the algorithm).
Log: For analyses, it would be nice to have a log value that shows the distance to the next waypoint. It helps a lot to see when the vehicle is facing the next waypoint. I am thinking of something similiar to the wp_dist value of the rover_pos_control module.
Finally, there are two more points, but they could also be my fault. I am not sure if these points are connected to the module. It worked with the rover_pos_control module, but not with yours:
-
Vehicle does not move back to launch position, although the last step in mission is āreturn to launchā. Instead the vehicle stops at the last waypoint.
-
I had to use the PWM MAIN section to assign the actuators. There was no movement when I assigned the actuators in PWM AUX section.
All in all, I am very happy with your module. It is already doing a very good job!
Hope this feedback will help you to improve the module!
Hi @Zugsepp1012,
Thank you very much for testing the module and your feedback!
It was especially interessting to see it work on a bigger rover since I only ever tested it on a small one.
In regard to your feedback:
Turning: The slow down effect is currently implemented in a very basic way, just slowing down the vehicle after it enters the acceptance radius of the WP. I am currently looking into slowing down the vehicle based on the steering input, that would improve this behaviour and could also be useful for manual mode to prevent roll over.
Steering: This is a very good idea, I will be looking into it!
Log: I already use that value inside the module so I can definitely add it to the log.
Return to launch: This is not yet implemented, but I agree that this is an important feature to add.
Actuator assignment: With my rover I use the AUX section for the motors, so the problem might be outside the module.
Thank you again for your indepth feedback, this really helps to improve the module!
As a side note: These improvements will probably not be part of the current PR, the plan is to first merge an initial ābasic versionā and then start adding more features in subsequent PRs.