Unable to operate motor with new VOXL2 IO board + firmware
-
Hello community,
I received new VOXL2 IO boards with new firmware + bootloader. I am working on SDK 1.1.2 with latest voxl-px4 dev branch firmware v1.14. I am unable to see any motor movement with my VOXL2 IO setup over my custom drone with PWM ESC. I am old user of VOXL2 platform and have worked on older PX4 version 1.12 where VOXL2 IO used to work seamlessly.
I did check the LED glowing on VOXL2 IO and there isn't any solid orange LED glowing like it used to on legacy boards+firmware's.
I have also upgraded VOXL2 IO firmware after receiving it by following this guide and it worked as per the documents.So now my setup seemss to be correct from hardware connection perspective. Few more details, I have connected VOXL2 IO to J19 and also configured my voxl-px4.conf to work with VOXL2 IO ESC. I currently havent connected any RC and have configured RC to be EXTERNAL in voxl-px4.conf.
Also I have flashed the voxl2 io parameters from voxl2_io_helper.
I am unable to see any motor movement neither my ESC calibration worked as per the guide over here.
Here are the PX4 logs :
voxl2:/$ /usr/bin/voxl-px4 [INFO] Reading from /etc/modalai/voxl-px4.conf Found DSP signature file [INFO] Daemon mode enabled ************************* GPS=AUTODETECT RC=EXTERNAL ESC=VOXL2_IO_PWM_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 Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete INFO [muorb] SLPI: muorb aggregator thread running INFO [muorb] muorb protobuf initalize method succeeded INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] succesfully did ADVERTISE_TEST_TYPE INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097656 INFO [muorb] succesfully did SUBSCRIBE_TEST_TYPE INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097655 INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097654 INFO [muorb] succesfully did TOPIC_TEST_TYPE INFO [muorb] succesfully did UNSUBSCRIBE_TEST_TYPE INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097653 INFO [muorb] muorb test passed ______ __ __ ___ | ___ \ \ \ / / / | | |_/ / \ V / / /| | | __/ / \ / /_| | | | / /^\ \ \___ | \_| \/ \/ |_/ px4 starting. INFO [px4] startup script: /bin/sh /usr/bin/voxl-px4-start 0 INFO [muorb] SLPI: Advertising remote topic log_message INFO [parameters] Starting param sync THREAD ************************* GPS: AUTODETECT RC: EXTERNAL ESC: VOXL2_IO_PWM_ESC POWER MANAGER: VOXLPM DISTANCE SENSOR: NONE OSD: DISABLE EXTRA STEPS: ************************* INFO [muorb] SLPI: Starting param sync THREAD Running on M0054 INFO [muorb] SLPI: before starting the qshell_entry task INFO [muorb] SLPI: Creating pthread qshell INFO [muorb] SLPI: Successfully created px4 task PX4_qshell with tid 2097652 INFO [muorb] SLPI: qshell entry..... INFO [muorb] SLPI: after starting the qshell_entry task INFO [muorb] SLPI: Init app map initialized INFO [param] selected parameter default file /data/px4/param/parameters INFO [muorb] SLPI: Marking DeviceNode(parameter_client_reset_request) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(parameter_client_reset_response) as advertised in process_remote_topic INFO [muorb] SLPI: Advertising remote topic parameter_update INFO [muorb] SLPI: Marking DeviceNode(parameter_client_set_value_request) as advertised in process_remote_to INFO [uORB] Marking DeviceNode(parameter_server_set_used_request) as advertised in process_remote_topic INFO [muorb] SLPI: Marking DeviceNode(parameter_server_set_used_response) as advertised in process_remote_to INFO [uORB] Marking DeviceNode(parameter_client_set_value_response) as advertised in process_remote_topic INFO [parameters] BSON document size 1471 bytes, decoded 1471 bytes (INT32:27, FLOAT:41) INFO [logger] logger started (mode=all) Starting IMU driver with no rotation INFO [qshell] Send cmd: 'icm42688p start -s' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: icm42688p start -s INFO [muorb] SLPI: arg0 = 'icm42688p' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-s' INFO [muorb] SLPI: *** SPI Device ID 0x26000a 2490378 INFO [uORB] Advertising remote topic sensor_accel INFO [uORB] Advertising remote topic sensor_gyro INFO [muorb] SLPI: ICM42688P::probe successful! INFO [muorb] SLPI: on SPI bus 1 INFO [muorb] SLPI: icm42688p #0 on SPI bus 1 INFO [muorb] SLPI: INFO [muorb] SLPI: >>> ICM42688P this: 3176eab0 INFO [muorb] SLPI: Ok executing command: icm42688p start -s INFO [uORB] Advertising remote topic qshell_retval INFO [muorb] SLPI: >>> ICM42688P this: 3176eab0 INFO [qshell] qshell return value timestamp: 405569400, local time: 402990753 INFO [muorb] SLPI: >>> ICM42688P this: 3176eab0 INFO [muorb] SLPI: Register interrupt b21d31a4 e61fedec 3176eab0 INFO [uORB] Advertising remote topic sensor_gyro_fifo INFO [uORB] Advertising remote topic sensor_accel_fifo INFO [uORB] Advertising remote topic imu_server INFO [qshell] Send cmd: 'icp101xx start -I -b 5' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: icp101xx start -I -b 5 INFO [muorb] SLPI: arg0 = 'icp101xx' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-I' INFO [muorb] SLPI: arg3 = '-b' INFO [muorb] SLPI: arg4 = '5' INFO [muorb] SLPI: *** I2C Device ID 0xb76329 12018473 INFO [muorb] SLPI: icp101xx #0 on I2C bus 5 INFO [muorb] SLPI: address 0x63 INFO [muorb] SLPI: INFO [muorb] SLPI: Ok executing command: icp101xx start -I -b 5 INFO [qshell] qshell return value timestamp: 405605733, local time: 403023790 Looking for qmc5883l magnetometer INFO [qshell] Send cmd: 'qmc5883l start -R 10 -X -b 1' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: qmc5883l start -R 10 -X -b 1 INFO [muorb] SLPI: arg0 = 'qmc5883l' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-R' INFO [muorb] SLPI: arg3 = '10' INFO [muorb] SLPI: arg4 = '-X' INFO [muorb] SLPI: arg5 = '-b' INFO [muorb] SLPI: arg6 = '1' INFO [muorb] SLPI: *** I2C Device ID 0x80d09 527625 ERROR [muorb] SLPI: i2c probe failed INFO [muorb] SLPI: PX4_qshell: no instance started (no device on bus?) ERROR [muorb] SLPI: Failed to execute command: qmc5883l start -R 10 -X -b 1 INFO [qshell] cmd returned with: -1 INFO [qshell] qshell return value timestamp: 405663367, local time: 403082132 ERROR [qshell] Command failed Looking for ist8310 magnetometer INFO [muorb] SLPI: >>> ICM42688P this: 3176eab0 INFO [qshell] Send cmd: 'ist8310 start -R 10 -X -b 1' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: ist8310 start -R 10 -X -b 1 INFO [muorb] SLPI: arg0 = 'ist8310' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-R' INFO [muorb] SLPI: arg3 = '10' INFO [muorb] SLPI: arg4 = '-X' INFO [muorb] SLPI: arg5 = '-b' INFO [muorb] SLPI: arg6 = '1' INFO [muorb] SLPI: *** I2C Device ID 0x60e09 396809 INFO [muorb] SLPI: ist8310 #0 on I2C bus 1 INFO [muorb] SLPI: (external) INFO [muorb] SLPI: address 0xE INFO [muorb] SLPI: rotation 10 INFO [muorb] SLPI: INFO [muorb] SLPI: Ok executing command: ist8310 start -R 10 -X -b 1 INFO [qshell] qshell return value timestamp: 405692917, local time: 403111814 INFO [qshell] Send cmd: 'gps start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: gps start INFO [muorb] SLPI: arg0 = 'gps' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Creating pthread gps INFO [muorb] SLPI: Successfully created px4 task PX4_gps with tid 2097647 INFO [muorb] SLPI: Ok executing command: gps start INFO [qshell] qshell return value timestamp: 405718456, local time: 403139023 Looking for ncp5623c RGB LED INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [qshell] Send cmd: 'rgbled_ncp5623c start -X -b 1 -f 400 -a 56' INFO [muorb] SLPI: qshell gotten: rgbled_ncp5623c start -X -b 1 -f 400 -a 56 INFO [muorb] SLPI: arg0 = 'rgbled_ncp5623c' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-X' INFO [muorb] SLPI: arg3 = '-b' INFO [muorb] SLPI: arg4 = '1' INFO [muorb] SLPI: arg5 = '-f' INFO [muorb] SLPI: arg6 = '400' INFO [muorb] SLPI: arg7 = '-a' INFO [muorb] SLPI: arg8 = '56' INFO [muorb] SLPI: *** I2C Device ID 0x7b3809 8075273 INFO [muorb] SLPI: rgbled_ncp5623c #0 on I2C bus 1 INFO [muorb] SLPI: (external) INFO [muorb] SLPI: address 0x38 INFO [muorb] SLPI: INFO [muorb] SLPI: Ok executing command: rgbled_ncp5623c start -X -b 1 -f 400 -a 56 INFO [qshell] qshell return value timestamp: 405749413, local time: 403172376 INFO [muorb] SLPI: GPS UART baudrate set to 115200 INFO [uORB] Advertising remote topic sensor_mag INFO [qshell] Send cmd: 'pca9685_pwm_out start -a 0x40 -b 4' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: pca9685_pwm_out start -a 0x40 -b 4 INFO [muorb] SLPI: arg0 = 'pca9685_pwm_out' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-a' INFO [muorb] SLPI: arg3 = '0x40' INFO [muorb] SLPI: arg4 = '-b' INFO [muorb] SLPI: arg5 = '4' INFO [uORB] Advertising remote topic sensor_baro INFO [uORB] Advertising remote topic actuator_outputs INFO [muorb] SLPI: *** I2C Device ID 0x694021 6897697 INFO [muorb] SLPI: running on I2C bus 4 address 0x40 INFO [muorb] SLPI: Ok executing command: pca9685_pwm_out start -a 0x40 -b 4 INFO [qshell] qshell return value timestamp: 406059313, local time: 403480313 INFO [muorb] SLPI: PCA9685 PWM frequency: target=50.00 real=50.03 Starting VOXL IO for PWM ESC without SBUS RC INFO [qshell] Send cmd: 'voxl2_io start -e' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: voxl2_io start -e INFO [muorb] SLPI: arg0 = 'voxl2_io' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-e' INFO [uORB] Marking DeviceNode(actuator_outputs) as advertised in process_remote_topic INFO [muorb] SLPI: M0065 using external RC INFO [muorb] SLPI: Opened UART connection to M0065 device on port 2 INFO [muorb] SLPI: Ok executing command: voxl2_io start -e INFO [qshell] qshell return value timestamp: 406159780, local time: 403579367 INFO [qshell] Send cmd: 'voxlpm start -X -b 2' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: voxlpm start -X -b 2 INFO [muorb] SLPI: arg0 = 'voxlpm' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-X' INFO [muorb] SLPI: arg3 = '-b' INFO [muorb] SLPI: arg4 = '2' INFO [muorb] SLPI: *** I2C Device ID 0xd24411 13779985 INFO [muorb] SLPI: Set i2c address 0x6a, fd 5 INFO [muorb] SLPI: Set i2c address 0x44, fd 5 ERROR [muorb] SLPI: i2c probe failed INFO [muorb] SLPI: PX4_qshell: no instance started (no device on bus?) ERROR [muorb] SLPI: Failed to execute command: voxlpm start -X -b 2 INFO [qshell] cmd returned with: -1 INFO [qshell] qshell return value timestamp: 406252795, local time: 403671638 ERROR [qshell] Command failed INFO [qshell] Send cmd: 'sensors start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: sensors start INFO [muorb] SLPI: arg0 = 'sensors' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic sensor_selection INFO [uORB] Advertising remote topic sensors_status_imu INFO [uORB] Advertising remote topic vehicle_acceleration INFO [uORB] Advertising remote topic vehicle_angular_velocity INFO [uORB] Advertising remote topic sensor_combined INFO [uORB] Advertising remote topic vehicle_air_data INFO [uORB] Advertising remote topic vehicle_gps_position ERROR [muorb] SLPI: Timeout waiting for parameter_server_set_used_response for CAL_MAG_SIDES INFO [uORB] Advertising remote topic sensors_status_baro INFO [uORB] Advertising remote topic vehicle_magnetometer INFO [uORB] Advertising remote topic sensor_preflight_mag INFO [uORB] Advertising remote topic sensors_status_mag INFO [uORB] Advertising remote topic vehicle_imu INFO [uORB] Advertising remote topic vehicle_imu_status INFO [muorb] SLPI: Ok executing command: sensors start INFO [qshell] qshell return value timestamp: 406550446, local time: 403970891 INFO [qshell] Send cmd: 'ekf2 start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: ekf2 start INFO [muorb] SLPI: arg0 = 'ekf2' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic vehicle_attitude INFO [uORB] Advertising remote topic vehicle_local_position INFO [uORB] Advertising remote topic estimator_event_flags INFO [uORB] Advertising remote topic estimator_innovation_test_ratios INFO [uORB] Advertising remote topic estimator_innovation_variances INFO [uORB] Advertising remote topic estimator_innovations INFO [uORB] Advertising remote topic estimator_sensor_bias INFO [uORB] Advertising remote topic estimator_states INFO [uORB] Advertising remote topic estimator_status_flags INFO [uORB] Advertising remote topic estimator_status INFO [muorb] SLPI: Ok executing command: ekf2 start INFO [qshell] qshell return value timestamp: 406956854, local time: 404377570 INFO [uORB] Advertising remote topic ekf2_timestamps INFO [uORB] Advertising remote topic vehicle_odometry INFO [uORB] Advertising remote topic estimator_aid_src_fake_pos INFO [uORB] Advertising remote topic estimator_aid_src_fake_hgt INFO [uORB] Advertising remote topic estimator_aid_src_mag_heading INFO [uORB] Advertising remote topic estimator_aid_src_mag INFO [uORB] Advertising remote topic estimator_aid_src_gravity INFO [qshell] Send cmd: 'mc_pos_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_pos_control start INFO [muorb] SLPI: arg0 = 'mc_pos_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic estimator_aid_src_baro_hgt INFO [uORB] Advertising remote topic takeoff_status INFO [muorb] SLPI: Ok executing command: mc_pos_control start INFO [qshell] qshell return value timestamp: 407096686, local time: 404516349 INFO [qshell] Send cmd: 'mc_att_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_att_control start INFO [muorb] SLPI: arg0 = 'mc_att_control' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: mc_att_control start INFO [qshell] qshell return value timestamp: 407163156, local time: 404584548 INFO [qshell] Send cmd: 'mc_rate_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_rate_control start INFO [muorb] SLPI: arg0 = 'mc_rate_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic rate_ctrl_status INFO [muorb] SLPI: Ok executing command: mc_rate_control start INFO [qshell] qshell return value timestamp: 407316409, local time: 404736065 INFO [qshell] Send cmd: 'mc_hover_thrust_estimator start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_hover_thrust_estimator start INFO [muorb] SLPI: arg0 = 'mc_hover_thrust_estimator' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: mc_hover_thrust_estimator start INFO [qshell] qshell return value timestamp: 407378340, local time: 404797422 INFO [qshell] Send cmd: 'mc_autotune_attitude_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_autotune_attitude_control start INFO [muorb] SLPI: arg0 = 'mc_autotune_attitude_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic autotune_attitude_control_status INFO [muorb] SLPI: Ok executing command: mc_autotune_attitude_control start INFO [qshell] qshell return value timestamp: 407434803, local time: 404854208 INFO [qshell] Send cmd: 'land_detector start multicopter' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: land_detector start multicopter INFO [muorb] SLPI: arg0 = 'land_detector' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = 'multicopter' INFO [muorb] SLPI: Ok executing command: land_detector start multicopter INFO [qshell] qshell return value timestamp: 407499875, local time: 404920485 INFO [uORB] Advertising remote topic vehicle_land_detected INFO [qshell] Send cmd: 'manual_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: manual_control start INFO [muorb] SLPI: arg0 = 'manual_control' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: manual_control start INFO [qshell] qshell return value timestamp: 407572388, local time: 404992683 INFO [uORB] Advertising remote topic manual_control_setpoint INFO [qshell] Send cmd: 'control_allocator start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: control_allocator start INFO [muorb] SLPI: arg0 = 'control_allocator' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic control_allocator_status INFO [uORB] Marking DeviceNode(control_allocator_status) as advertised in process_remote_topic INFO [uORB] Advertising remote topic actuator_motors INFO [uORB] Advertising remote topic actuator_servos INFO [uORB] Advertising remote topic actuator_servos_trim INFO [muorb] SLPI: Ok executing command: control_allocator start INFO [qshell] qshell return value timestamp: 407962989, local time: 405381907 INFO [qshell] Send cmd: 'load_mon start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: load_mon start INFO [muorb] SLPI: arg0 = 'load_mon' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: load_mon start INFO [uORB] Advertising remote topic cpuload INFO [qshell] qshell return value timestamp: 408005112, local time: 405424756 INFO [qshell] Send cmd: 'commander start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: commander start INFO [muorb] SLPI: arg0 = 'commander' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Creating pthread commander INFO [muorb] SLPI: Successfully created px4 task PX4_commander with tid 2097639 INFO [uORB] Advertising remote topic led_control INFO [muorb] SLPI: LED: open /dev/led0 failed (22) INFO [uORB] Advertising remote topic tune_control INFO [muorb] SLPI: Ok executing command: commander start INFO [qshell] qshell return value timestamp: 408525836, local time: 405947754 INFO [uORB] Advertising remote topic event INFO [uORB] Advertising remote topic mavlink_log INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [uORB] Advertising remote topic health_report INFO [uORB] Advertising remote topic failsafe_flags INFO [uORB] Advertising remote topic actuator_armed INFO [uORB] Advertising remote topic vehicle_control_mode INFO [uORB] Advertising remote topic vehicle_thrust_setpoint INFO [uORB] Advertising remote topic vehicle_torque_setpoint INFO [uORB] Advertising remote topic vehicle_attitude_setpoint INFO [uORB] Advertising remote topic vehicle_rates_setpoint INFO [uORB] Advertising remote topic vehicle_status INFO [uORB] Advertising remote topic failure_detector_status INFO [qshell] Send cmd: 'flight_mode_manager start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: flight_mode_manager start INFO [muorb] SLPI: arg0 = 'flight_mode_manager' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic vehicle_command INFO [muorb] SLPI: Ok executing command: flight_mode_manager start INFO [qshell] qshell return value timestamp: 408709856, local time: 406128859 INFO [dataman] data manager file '/data/px4/dataman' size is 7866640 bytes INFO [muorb] SLPI: Advertising remote topic transponder_report INFO [muorb] SLPI: Advertising remote topic rtl_time_estimate INFO [muorb] SLPI: Advertising remote topic position_setpoint_triplet INFO [modal_io_bridge] Modal IO Bridge driver starting INFO [mavlink] mode: Onboard, data rate: 100000 B/s on udp port 14556 remote port 14557 INFO [muorb] SLPI: Advertising remote topic telemetry_status INFO [mavlink] partner IP: 127.0.0.1 INFO [muorb] SLPI: Advertising remote topic offboard_control_mode INFO [muorb] SLPI: Advertising remote topic vehicle_visual_odometry INFO [muorb] SLPI: Advertising remote topic obstacle_distance INFO [muorb] SLPI: GPS UART baudrate set to 9600 INFO [muorb] SLPI: Advertising remote topic timesync_status INFO [uORB] Advertising remote topic actuator_controls_status_0 INFO [mavlink] mode: Normal, data rate: 100000 B/s on udp port 14558 remote port 14559 INFO [muorb] SLPI: Marking DeviceNode(telemetry_status) as advertised in process_remote_topic INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network) INFO [px4] Startup script returned successfully INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: GPS UART baudrate set to 38400 INFO [muorb] SLPI: u-blox firmware version: SPG 3.01 INFO [muorb] SLPI: u-blox protocol version: 18.00 INFO [muorb] SLPI: u-blox module: NEO-M8N-0 INFO [uORB] Advertising remote topic sensor_gps INFO [uORB] Advertising remote topic estimator_gps_status INFO [uORB] Advertising remote topic estimator_aid_src_gnss_hgt INFO [uORB] Advertising remote topic estimator_aid_src_gnss_pos INFO [uORB] Advertising remote topic estimator_aid_src_gnss_vel INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: GPS Horizontal Pos Error too high INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: not enough GPS Satellites INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: GPS Horizontal Pos Error too high INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Advertising remote topic actuator_test INFO [muorb] SLPI: Marking DeviceNode(actuator_test) as advertised in process_remote_topic INFO [muorb] SLPI: Marking DeviceNode(actuator_test) as advertised in process_remote_topic INFO [muorb] SLPI: Marking DeviceNode(actuator_test) as advertised in process_remote_topic INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: vertical velocity unstable INFO [muorb] SLPI: Preflight: GPS Horizontal Pos Error too high INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: GPS Horizontal Pos Error too high INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Marking DeviceNode(actuator_test) as advertised in process_remote_topic INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: not enough GPS Satellites INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: GPS Horizontal Pos Error too high INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Marking DeviceNode(actuator_test) as advertised in process_remote_topic INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: not enough GPS Satellites INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Accel 0 uncalibrated INFO [muorb] SLPI: Preflight: GPS Horizontal Pos Error too high INFO [muorb] SLPI: Preflight Fail: Attitude failure (roll) INFO [muorb] SLPI: Preflight Fail: Gyro 0 uncalibrated INFO [muorb] SLPI: Preflight Fail: Compass 0 uncalibrated
Also when I execute pc4-actuator-test from commandline, it also does nothing.
voxl2:/$ px4-actuator_test set -m 1 -v 0.1 -t 1 WARN [uORB] orb_advertise_multi: failed to set queue size
I would really appreciate if someone can help me quickly debug my problem. @Alex-Kushleyev @Eric-Katzfey
-
@Aaky ,
Can you please try running voxl2 io px4 driver in debug mode (using
-v
flag), it sets the debug mode on, as shown here : https://github.com/modalai/px4-firmware/blob/voxl-dev/src/drivers/voxl2_io/voxl2_io.cpp#L608You can modify
/usr/bin/voxl-px4-start
and add-v
to the command that starts upvoxl2_io
driver for your use case that should look like thisqshell voxl2_io start .... -v
Then when you call calibrate escs function (https://github.com/modalai/px4-firmware/blob/voxl-dev/src/drivers/voxl2_io/voxl2_io.cpp#L690) it should print out some information in debug mode, you should check if that is printing out.
Also please check the behavior of the blue led on the M0065 board. The blue LED will flash very quickly (which may appear as almost steady on) when PWM commands are being sent to it from PX4 (such as actuator test).
We will looking adding some more debugging information to help diagnose such issues further, but meanwhile please try to see if you have any useful output when you enable debugging (verbose) mode in the voxl2 io driver.
Alex
-
@Alex-Kushleyev Thanks for the response. I solved this problem, it was regarding the UART port number. Since I had connected VOXL2IO to J19, I had to set port number to 7, post which board started to work just fine. I think, this section is missing in the documents which can be added, just a suggestion.
Btw, is there any way to see what are PWM output's been published by VOXL2IO in Qground control? I wanted to see that because post arming my motors dont spin at all with my Tmotor ESC (I tried performing ESC calibration but final happy tone didnt came up.) and all motors start spinning at 50% throttle on our S-bus based RC. I tried setting MPC_THR_MIN but it didnt help me get my motors spin on arm. I know its maybe PX4 specific query but let me know if you have any clue.
-
@Aaky , that is great that you figured it out.
We would like to improve the documentation. We have a few use cases listed here : https://docs.modalai.com/voxl2-io-user-guide/#voxl-2-io-sbus-input-and-pwm-output and we suggest connecting the VOXL2 IO board to J18 if you are not using ModalAI UART ESCs. Is there any particular reason why you did not do that? It may be simpler for you to use one of our standard configuration options.
Alex
-
@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.