I am experiencing some issues while using the APM flight controller(Copter 4.5.7) to control an indoor helicopter, specifically related to optical flow and the distance sensor (RNGFND). Below are the details:
The configuration is as follows (see attached diagram):
I am able to enter both Loiter and AltHold modes. However, when I attempt to increase the throttle further, the aircraft oscillates at a certain altitude and is unable to ascend. Please refer to the logs at timestamps 00:02:05 and 00:06:21, where you can see the PSCD->TPD, PD, and RCIN->C3 data.
Thank you for your reply! I’ve uploaded the log file for further analysis, which you can access now. Additionally, I am using the ArduPilot firmware version 4.5.7. I am wondering why this version might be causing issues with the system, or if there is a specific reason why 4.5.7 isn’t recommended for this kind of setup.
It is a traditional toy helicopter, using tof and optical flow to realize indoor hovering. I was just wondering why i can’t raise the altitude while in loiter mode.
I also see you have a throttle based notch filter (INS_HNTC2_MODE,1). Those don’t work properly with the H_RSC_MODE,2. They end up following the collective, not the motor speed. You may be better to set a fixed notch filter.
Thanks for your reply. Let me add more details about this issue. When I realized this problem, I tried to disable the TOF, then the altitude limitation disappeared in ALTHOLD mode. However, indoor loiter cannot be changed into without TOF. Thus, I think the altitude limitation is not caused by vibration.
The problem is that position controlled modes (like Loiter) will not allow your heli to climb past the altitude limit dictated by the RFND sensor you are using (should be about 1.2m according to the sensor you are using), this to avoid failsafe triggering.
Furthermore, if you look into your RFND log messages you will also see the status changing when approaching that altitude (4->3).
Of course this does not affect modes like Alt-Hold, indeed it was allowed to climb up further.
Thank you for your reply. In fact, when I try to use RNGFND in ALT HOLD mode, I also encounter height limitations. Additionally, in LOITER mode, when the altitude limit is reached, the RNGFND state is not 3, and it has not exceeded the maximum measurement range (RNGFND1_MAX_CM = 200 cm).
This is incorrect, indeed the sensor readings appear to be not reliable well before that limit.
Official guide recommends 1.2m for the sensor I believe you have installed.
Perhaps it would help if you also listed the sensors you are using (rather than guessing them looking through your parameters).
Hi, Ferrosan.I am using the VL53L1X as a distance sensor. I checked the official documentation, and it does indeed recommend using the SHORT mode for height ranges up to 1.3 meters. However, when flying in Stabilize mode, I found that accurate measurements can be made up to approximately 2 meters. Only when the height exceeds 2 meters do I encounter the no data and bad lidar health warnings. Does this mean I can actually use the VL53L1X normally within 2 meters?
Additionally, I am curious—despite the physical measurement limitation of the distance sensor (assumed to be 1.3 meters), according to the EK3_RNG_USE_HGT=70 parameter, if the flight height exceeds 1.3 * 70%, the flight controller should instead use the barometer as the primary altitude source, rather than being limited by the altitude limit of the VL53L1.
Thank you for your response. I’ve located the height limit code related to RNGFND usage, and confirmed that the altitude restriction is indeed caused by the rangefinder’s measurement range limitations.
// provides the height limit to be observed by the control loops
// returns false if no height limiting is required
// this is needed to ensure the vehicle does not fly too high when using optical flow navigation
bool NavEKF3_core::getHeightControlLimit(float &height) const
{
// only ask for limiting if we are doing optical flow navigation
if (frontend->sources.useVelXYSource(AP_NavEKF_Source::SourceXY::OPTFLOW) && (PV_AidingMode == AID_RELATIVE) && flowDataValid) {
// If are doing optical flow nav, ensure the height above ground is within range finder limits after accounting for vehicle tilt and control errors
const auto *_rng = dal.rangefinder();
if (_rng == nullptr) {
// we really, really shouldn't be here.
return false;
}
height = MAX(float(_rng->max_distance_cm_orient(ROTATION_PITCH_270)) * 0.007f - 1.0f, 1.0f);
// If we are are not using the range finder as the height reference, then compensate for the difference between terrain and EKF origin
if (frontend->sources.getPosZSource() != AP_NavEKF_Source::SourceZ::RANGEFINDER) {
height -= terrainState;
}
return true;
} else {
return false;
}
}