Skip to content

Common Issues in Operation

Alp edited this page Oct 24, 2024 · 3 revisions

This page contains some common issues and tips that may be useful when working with the rover.

Jerking motion of the rover

Sometimes the rover may exhibit jerking motion when it is stationary. This might caused by the noise present in the RC signal carried from RC receiver to Pi Picos. The noise can be filtered out by using an average filter. The filter is implemented in central_hub.py with the window size (RC_FILTER_WINDOW_SIZE) currently set to 3. To achieve better filtering, the window size can be increased. However, increasing the window size will increase the delay in the control signal.

Mavlink connection not found by Rpi

If the return value of the function initialise_mavlink() is (system 0 component 0) and the error message of "Message HEARTBEAT not found" is displayed, it means that the Rpi is not able to connect to the flight controller. Some possible solutions are:

  1. Try to establish the connection again by calling the function initialise_mavlink() again.
  2. Try to connect to the flight controller using mavproxy (e.g. mavproxy.py --master=/dev/ttyAMA0 --baudrate 57600) and check if the connection is established. Reboot the flight controller and rerun the script.
  3. Power cycle the entire rover.

A working connection should display "Heartbeat from MAVLink system (system 1 component 0)".

Weighting of EKF sources in ArduRover

The weigth of the sources in the EKF can be adjusted by the respective noise parameters such as EK3_MAG_M_NSE, EK3_WENC_VERR etc. The noise are related to the resolution of the sensors but there are other factors that can affect the RMS noise of each sensor. The following table contains the datasheets of the sensors used in the rover and the noise values estimated.

Detailed information on the noise parameters can be found in the EKF documentation.

Sensor Noise (minimum) Datasheet Notes
Magnetometer RM3100 15nT = 0.00015 gauss https://www.tri-m.com/products/pni/RM3100-User-Manual.pdf Cycle counts of Magnetometer is assumed to be the default value of 200.
Ardupilot param EK3_MAG_M_NSE only allows minimum of 0.01 gauss
EK3_YAW_M_NSE takes the noise in yaw angle measurement in radians
Optical flow PMW3901 N/A https://wiki.bitcraze.io/\_media/projects:crazyflie2:expansionboards:pot0189-pmw3901mb-txqt-ds-r1.00-200317_20170331160807_public.pdf EK3_FLOW_M_NSE has a min value of 0.05 rad/s
The issue is to convert the information below into noise:
Speed = 7.4 rad/s
Resolution = 16-bit
IMU
MPU6000
ICM42605
ICM:
Gyro: 0.001 rad/s
Acc: 0.005 m/s^2

MPU:
Gyro: 0.001 rad/s
Acc: 0.005 m/s^2
https://invensense.tdk.com/wp-content/uploads/2015/02/MPU-6000-Datasheet1.pdf
https://invensense.tdk.com/wp-content/uploads/2022/09/DS-000292-ICM-42605-v1.7.pdf
Unsure of the IMU configuration used by the h743 flight controller, assuming the largest range (lower sensitivity, higher noise) and the noise is assumed to be equivalent to 1 LSB
Wheel encoders No spec found EK3_WENC_VERR is set to 0.1 m/s

Setting EKF sources

The EKF sources can be set in the ArduRover parameters as listed in here. Care should be taken when fusing the velocity sources as shown below: image

Compass issue

The compass may not be calibrated properly if there is a magfield error on ground station which will prevent arming of the rover. The compass can be calibrated by rotating the rover in different axis as per the instructions in the ArduPilot documentation. It can be done using the Mission Planner or QGroundControl.

Another faster way of calibrating the compass can be achieved using the Quick Calibration feature in QGroundControl (not available in IOS). The rover should be oriented towards North (More details). However, this method requires known GPS location and seems to be less accurate than the manual calibration.

Another factor that might affect the accuracy of this internal compass is the power supply cables and motors. This can be checked using Mission Planner's CompassMot feature as described here.

Bypass Encoder (Low-level)

The encoders are currently bypassed as the front left wheel encoder is faulty. To reenable wheel encoders and allow speed control, either setting the parameter BYPASS_ENCODER to false or remove if clause everywhere in motor_controller.py.