Unable to operate motor with new VOXL2 IO board + firmware
-
@Alex-Kushleyev There isn't any reason for us to not use J18 for VOXL2 IO Control. We will look into that direction. I am more worried why my ESC calibration isn't completing with happy tone. Logs says calibration is successful tough but I dont hear happy tone like that in this video.
-
@Aaky , can you please describe what sounds your ESCs are generating during the esc calibration?
the VOXL2 IO board sends out the standard PWM pulses (in range of 1-2ms). Specifically, the procedure is as follows:
- PWM output cable is unplugged from VOXL2 IO board
- ESCs receive no signal
- ESC calibration procedure is initiated by user
- once the PWM output cable is plugged back in and 10 seconds expire, the VOXL2 IO will
- send out PWM_MAX (2000us) for 3 seconds
- send out PWM_MIN (1000us) for 4 seconds
- calibration process is completed
Is it possible that your ESC does not support the calibration procedure?
-
@Alex-Kushleyev Thanks for the detailed steps provided.
I am using this ESC from Tmotor.I did follow all the mentioned steps for ESC calibration twice. On my setup, once I plug in the PWM output cable after initiating calibration command from terminal, I just hear a welcome tone from ESC which maybe tells about PWM signals been received by ESC but after that ESC isn't reacting to PWM_MAX and PWM_MIN commands sent by voxl2_io module so it just stays quiet.
On my first attempt of calibration, Motor went to PWM_MAX during calibration and were spinning as well but even then the beep count and last ESC calibration completion tone wasn't heard.
Is it possible that your ESC does not support the calibration procedure?
I do not know about that. Do you have an idea about this Tmotor Velox ESC supporting calibration?
Also on a seperate note, when I checked post arming my actuator_outputs topic with "px4-listener actuator_outputs", all the values are going out as 0 so my motors aren't spinning while I arm it. Aircraft still takeoff at 63% throttle but of course the movement of motors is extremely sudden then.
-
@Aaky , can you please try the actuator test feature in PX4 to spin the motors (without propellers) and see at what command the motors start spinning?
-
@Alex-Kushleyev I tried actuator test feature and I can see with this command "px4-actuator_test set -m 1 -v 0.05 -t 1" motor start to spin. If I check actuator_outputs data with px4-listener it shows to be 40 units for that particular motors.
-
@Aaky ok, that sounds reasonable.
The way the voxl2_io hardware board is set up, it receives a command that ranges from 0 to 800 (0 to 100%), so our modal_io driver does the conversion to scale 0.0... 1.0 to 0..800 and then the voxl2_io board, when it receives the command via UART, it converts 0..800 command to 1000..2000us pwm signal.
So if you commanded 0.05, that is 0.05* 800 = 40, so this would result in 1050us pulse sent to the ESC, so ESC would spin very slowly.
For now, maybe skip the ESC calibration part, it seems that the ESC is responding correctly to actuator test (you can check all 4 motors).
Since the actuator test seems to be working, perhaps you should try to do the arming and takeoff command ( with propellers ***** OFF ***** for safety) while collecting a PX4 log and then you can use flight-review to check what you were commanding with RC and the value of actuator outputs. Since you are saying that when you try to take off (in manual mode??) there actuator_outputs were zero until you raised the throttle to a high value and then motors suddenly spun up to high rpm, you should see what happened on the flight review plots. Maybe you were in a different flight mode?
-
@Alex-Kushleyev Thanks for the clarification. I was in position flight mode where post arming due to 0 units been streamed to voxl2_io commands as per above description motors dont spin. I will surely look into flight review as per your suggestion.
How can we increase this arming command been sent to voxl2_io to be somewhere near to 50 so that motors will start to spin? Is there any parameter to do that or I will have to dig into code?
-
@Aaky , voxl2_io driver has a parameter https://github.com/modalai/px4-firmware/blob/voxl-dev/src/drivers/voxl2_io/voxl2_io_params.c#L54 (
VOXL2_IO_MIN
) -- you should be able to adjust that via PX4 params from 1000 (default) to 1050, so that 0..800 range gets scaled to 1050..2000 on the voxl2_io board. -
@Alex-Kushleyev I tried doing that. With that, motor start spinning without even arming.
-
@Aaky , it would help if you created a PX4 log, which will show what you are doing with RC and what actuator outputs are being generated. You are ok with sharing the log, you can upload it to https://review.px4.io/ and send a link to the review page.
-
@Alex-Kushleyev Yes. Please find log file over this link. Let me know your analysis.
-
@Alex-Kushleyev Any luck reviewing my logs?
-
@Aaky , sorry about the delay.
In your log, it looks like you are in Position mode, which is what I think you intended. I see that during start-up the, motor outputs ramp from 0 to about 0.45 in about half a second.
Can you please describe exactly what you saw during that start of the test? I do not see anything abnormal when i look at roll, pitch, yaw angles during the motor start-up.
If you look at a plot of angular rate, you can detect when the motors actually start spinning:
The motor command became non-zero at 13:36:750 (or so) and it looks like there was some movement (based on Roll angular rate) that started around the same time. So, it seems the ESC is responding correctly.
However, the thrust goes from zero to hover thrust in about 0.5 seconds, which is pretty fast, so maybe this seems surprising to you? Did the vehicle fly well?
-
@Alex-Kushleyev Thank you for the response. Yes the vehicle flies well, there isnt any issue in flying. Actually when we arm the UAV on ground, motors dont spin at all and when user raises the RC stick to 62.5% motors spin at that point only and achieve the hover throttle.
On all the normal vehicles which I have flown till date in PX4, motor do always spin on arm and post manual RC based throttle raise/Auto take off raises the throttle to hover conditions but with this setup I am seeing motors dont spin at all and actuator_outputs topic shows 0 units been commanded to voxl2_io. How can we increase this arming command to actuator to something say 0.1/0.05?
-
@Aaky I believe the reason why your drone starts increasing rpm only when you raise the throttle above 50% is because you are in a position mode, in which the thrust control stick is controlling Z velocity. So in order to command the drone to take off, you have to raise the stick above 0 (middle position).
However, yes, it seems there is another issue, which is motors not spinning at idle, which means the minimum commanded PWM signal is below the threshold for the ESC to respond. This is dangerous because this could mean that the flight controller could send such low command during flight and motor(s) may turn off inadvertently.
I believe i know what the issue is, but in order to fix it, the px4 package needs to be rebuilt. Are you set up to build px4 for voxl2? if not i can make a change and build it for you to try. Can you tell me which version of px4 you are using?
voxl-version | grep px4
. I can make a change based on your current version of px4 package. -
@Alex-Kushleyev Thanks for the update. Yes I have setup to build px4 firmware on my machine. Please provide me instructions to correct this problem.
-
@Aaky , please to update this value from 1000 to 1100 which will increase the minimum PWM value that is sent to the motors : https://github.com/modalai/px4-firmware/blob/voxl-dev/src/drivers/voxl2_io/voxl2_io.hpp#L137 . However, do not recalibrate the ESC with this updated value, since it will reset your ESC minimum value also to 1100. Your commanded PWM value should never get close to the absolute minimum value that the ESC starts spinning. Otherwise, your motor can stop in flight.
So if the calibration was done at 1000us minimum signal, it is recommended to set the normal operating minimum at around 1100.
Please try this and let me know if it solves your issue with motors not spinning up when you arm the vehicle.
Alex
-
@Alex-Kushleyev I have modified the firmware and also built the same. I used install-voxl.sh script to manually place the binaries in voxl2 and post that if I try to run voxl-px4 I am getting following error:
voxl2:/$ /usr/bin/voxl-px4 [INFO] Reading from /etc/modalai/voxl-px4.conf Found DSP signature file [INFO] Daemon mode enabled ************************* GPS=AUTODETECT RC=CRSF_RAW ESC=VOXL_ESC POWER MANAGER=VOXLPM DISTANCE SENSOR=NONE OSD=DISABLE DAEMON_MODE=ENABLE SENSOR_CAL=ACTUAL EXTRA STEPS: ************************* INFO [px4] mlockall() enabled. PX4's virtual address space is locked into RAM. INFO [px4] assuming working directory is rootfs, no symlinks needed. INFO [muorb] Got muorb init command Sending initialization request INFO [muorb] muorb protobuf initalize method succeeded INFO [muorb] SLPI: Creating pthread test_MUORB ERROR [muorb] SLPI: Hit maximum number of threads INFO [muorb] succesfully did ADVERTISE_TEST_TYPE ERROR [muorb] Test timed out waiting for response px4: symbol lookup error: px4: undefined symbol: fc_sensor_get_time_offset
Some undefined symbol problem. What should be further steps to debug this?
-
@Alex-Kushleyev Got this fixed after picking debians from this link for libfc and modalslpi. Yet to test the behaviour of motors on arm.
-
@Alex-Kushleyev I tried with updating the firmware as you mentioned to update PWM minimum value from 1000 to 1100 in voxl2_io.hpp file. With these changes I tried to arm UAV in Altitude flight mode in indoors but still motors weren't spinning and actuator_outputs topic shows all zeros for all the four motors still. Let me know further steps.