Hello everyone,
So today I got some time with the robot in our water basin and I was able to test a few things. I focused on using only ArduSub for now.
Test 1: set throttle to stick to the wall
case JSButton::button_function_t::k_custom_1:
if (held) {
motors.set_throttle(1.0F);
}
break;
This worked so-so. When I kept pressing the assigned button, the four horizontal thrusters kept spinning, although not with full speed and not simultaneously. The four thrusters did not spin all the time, more like half the time (quickly alternating between spinning and stopping), and two thrusters spun more slowly than the other two for no obvious reason. It seems like Sub::handle_jsbutton_press()
is not called with high enough frequency for this to work permanently.
But in any case, my intention was that I would just push the button once and the throttle thrusters would keep spinning at full speed until I push another button to turn them off again. So this does not seem like my pathway to success.
By the way, what is the difference between
motors.set_throttle(1.0F);
and
attitude_control.set_throttle_out(1.0F, false, g.throttle_filt);
?
I tried both versions with exactly the same result as decribed above, so I’m wondering if they function the same in the background.
Test 2: set pitch to turn vehicle
case JSButton::button_function_t::k_custom_2:
if (held) {
set_mode(STABILIZE, MODE_REASON_TX_COMMAND); //copied from line 163
attitude_control.input_euler_angle_roll_pitch_yaw(0.0F, 80.0F, 0.0F, false);
}
break;
This also did not work as expected. When I kept pressing the button, the ROV rolled very slightly to the left, reaching an angle of maybe 10 degrees. There was no movement along the pitch axis. Again in the same manner as in the first test with the throttle, the thrusters did not spin with full speed, however, due to STABILIZE mode, the ROV held the 10 degrees angle when I let go of the button.
I also tried setting the pitch using the Quaternion function
attitude_control.input_quaternion(Quaternion(sqrtf(0.5F), 0.0F, 0.0F, sqrtf(0.5F)));
but this behaved in the same way as the euler angle function.
Test 3: manual “docking”, then STABILZE
We drove the ROV to our wall in MANUAL mode, toggled the roll-pitch button and held both sticks on the controller down, so that the ROV was vertical and pushing into the wall as intended. Then I changed into STABILIZE mode and let go of the sticks. The ROV stayed in roughly the same position - it did not hold the pitch angle of 90 degrees, more like 80 degrees - however, it stopped pushing into the wall. We tried exactly the same thing with DEPTH_HOLD mode and got exactly the same behaviour. So for our purpose, neither of these approaches will not work unless we find a way to also make the ROV move towards the wall continuously.
Conclusion
I am giving up on joystick.cpp
and will try pymavlink next, as described by @williangalvani in his answer. If that doesn’t work either, I will try making use of UserCode.cpp
or implement a new mode.