in the src/modules/navigator/precland.cpp,there is following source code:
bool PrecLand::check_state_conditions(PrecLandState state)
{
vehicle_local_position_s *vehicle_local_position = _navigator->get_local_position();
switch (state) {
case PrecLandState::Start:
return _search_cnt <= _param_pld_max_srch.get();
case PrecLandState::HorizontalApproach:
// if we're already in this state, only want to make it invalid if we reached the target but can't see it anymore
if (_state == PrecLandState::HorizontalApproach) {
if (fabsf(_target_pose.x_abs - vehicle_local_position->x) < _param_pld_hacc_rad.get()
&& fabsf(_target_pose.y_abs - vehicle_local_position->y) < _param_pld_hacc_rad.get()) {
// we've reached the position where we last saw the target. If we don't see it now, we need to do something
return _target_pose_valid && _target_pose.abs_pos_valid;
} else {
// We've seen the target sometime during horizontal approach.
// Even if we don't see it as we're moving towards it, continue approaching last known location
return true;
}
}
// If we're trying to switch to this state, the target needs to be visible
return __target_pose_updated_ && _target_pose_valid && _target_pose.abs_pos_valid;
case PrecLandState::DescendAboveTarget:
// if we're already in this state, only leave it if target becomes unusable, don't care about horizontall offset to target
if (_state == PrecLandState::DescendAboveTarget) {
// if we're close to the ground, we're more critical of target timeouts so we quickly go into descend
if (check_state_conditions(PrecLandState::FinalApproach)) {
return hrt_absolute_time() - _target_pose.timestamp < 500000; // 0.5s
} else {
return _target_pose_valid && _target_pose.abs_pos_valid;
}
} else {
// if not already in this state, need to be above target to enter it
return _target_pose_updated && _target_pose.abs_pos_valid
&& fabsf(_target_pose.x_abs - vehicle_local_position->x) < _param_pld_hacc_rad.get()
&& fabsf(_target_pose.y_abs - vehicle_local_position->y) < _param_pld_hacc_rad.get();
}
...
...
the member variable "_target_pose_updated" is initialized to "False",and not be assigned "True" anywhere. so the precision landing state will never be switched to HorizontalApproach and DescendAboveTarget. I wondered that is it a bug?
some tips about it?
Coud you put the code between ``` to format it?
Also, it is updated, by ORB subscription.
orb_check(_target_pose_sub, &_target_pose_updated);
If there is a new message, the target will be updated. And the target is only updated by an external input. There are 2 places where the topic is advertised, MAVLink and convertion of the IRLock measurements.
$ grep -nr "orb_advertise(ORB_ID(landing_target_pose)" .
./src/modules/mavlink/mavlink_receiver.cpp:2173: _landing_target_pose_pub = orb_advertise(ORB_ID(landing_target_pose), &landing_target_pose);
./src/modules/landing_target_estimator/LandingTargetEstimator.cpp:224: _targetPosePub = orb_advertise(ORB_ID(landing_target_pose), &_target_pose);
Where is "orb_check(_target_pose_sub, &_target_pose_updated);"?I can't find it.
thanks.
FYI @okalachev
I got it,the source code is different between master and safe_landing_1.9 branch.which branch is stable?which branch can I test it on my drone?thanks.
Good catch @david6096, this appears to be a regression introduced by
https://github.com/PX4/Firmware/commit/e4ad9947637a6c7667cce7eecc9785fa13bebe81#diff-f45ed77ef246e60c91f6300a68629229L114
It looks like this is not yet broken in ~v1.9.0~v1.9.1, so you could use that for your tests until it's fixed on master.
You can test 1.9.1 I guess.
thanks,thanks very much.
let's keep this open until the problem is fixed. I'll try to make a PR soon.
Most helpful comment
let's keep this open until the problem is fixed. I'll try to make a PR soon.