@@ -167,6 +167,26 @@ void AP_Follow::clear_offsets_if_required()
167
167
168
168
// get target's estimated location
169
169
bool AP_Follow::get_target_location_and_velocity (Location &loc, Vector3f &vel_ned) const
170
+ {
171
+ Vector3p pos_ned;
172
+ Vector3f local_vel_ned; // so we either change both return parameters or neither
173
+ if (!get_target_position_and_velocity (pos_ned, local_vel_ned)) {
174
+ return false ;
175
+ }
176
+ if (!AP::ahrs ().get_location_from_origin_offset (loc, pos_ned * 0.01 )) {
177
+ return false ;
178
+ }
179
+ vel_ned = local_vel_ned;
180
+
181
+ if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
182
+ loc.change_alt_frame (Location::AltFrame::ABOVE_HOME);
183
+ }
184
+
185
+ return true ;
186
+ }
187
+
188
+ // get target's estimated location and velocity, both NED SI from origin
189
+ bool AP_Follow::get_target_position_and_velocity (Vector3p &pos_ned, Vector3f &vel_ned) const
170
190
{
171
191
// exit immediately if not enabled
172
192
if (!_enabled) {
@@ -187,16 +207,17 @@ bool AP_Follow::get_target_location_and_velocity(Location &loc, Vector3f &vel_ne
187
207
}
188
208
189
209
// project the vehicle position
190
- Location last_loc = _target_location ;
191
- last_loc. offset ( vel_ned.x * dt , vel_ned.y * dt) ;
192
- last_loc. alt -= vel_ned. z * 100 . 0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED
210
+ Vector3p projected_pos_ned = _target_position_ned ;
211
+ const Vector3p vel_ned_p { vel_ned.x , vel_ned.y , vel_ned. z } ;
212
+ projected_pos_ned += vel_ned_p * dt;
193
213
194
214
// return latest position estimate
195
- loc = last_loc ;
215
+ pos_ned = projected_pos_ned ;
196
216
return true ;
197
217
}
198
218
199
219
// get distance vector to target (in meters) and target's velocity all in NED frame
220
+ // FIXME: use the target_position_ned vector!
200
221
bool AP_Follow::get_target_dist_and_vel_ned (Vector3f &dist_ned, Vector3f &dist_with_offs, Vector3f &vel_ned)
201
222
{
202
223
// get our location
@@ -341,6 +362,7 @@ bool AP_Follow::handle_global_position_int_message(const mavlink_message_t &msg)
341
362
return false ;
342
363
}
343
364
365
+ Location _target_location;
344
366
_target_location.lat = packet.lat ;
345
367
_target_location.lng = packet.lon ;
346
368
@@ -352,6 +374,10 @@ bool AP_Follow::handle_global_position_int_message(const mavlink_message_t &msg)
352
374
// absolute altitude
353
375
_target_location.set_alt_cm (packet.alt / 10 , Location::AltFrame::ABSOLUTE);
354
376
}
377
+ if (!_target_location.get_vector_from_origin_NEU (_target_position_ned)) {
378
+ return false ;
379
+ }
380
+ _target_position_ned.z = -_target_position_ned.z ; // NEU->NED
355
381
356
382
_target_velocity_ned.x = packet.vx * 0 .01f ; // velocity north
357
383
_target_velocity_ned.y = packet.vy * 0 .01f ; // velocity east
@@ -386,18 +412,15 @@ bool AP_Follow::handle_follow_target_message(const mavlink_message_t &msg)
386
412
return false ;
387
413
}
388
414
389
- Location new_loc = _target_location ;
415
+ Location new_loc;
390
416
new_loc.lat = packet.lat ;
391
417
new_loc.lng = packet.lon ;
392
418
new_loc.set_alt_cm (packet.alt *100 , Location::AltFrame::ABSOLUTE);
393
419
394
- // FOLLOW_TARGET is always AMSL, change the provided alt to
395
- // above home if we are configured for relative alt
396
- if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE &&
397
- !new_loc.change_alt_frame (Location::AltFrame::ABOVE_HOME)) {
420
+ if (!new_loc.get_vector_from_origin_NEU (_target_position_ned)) {
398
421
return false ;
399
422
}
400
- _target_location = new_loc;
423
+ _target_position_ned. z = -_target_position_ned. z ; // NEU->NED
401
424
402
425
if (packet.est_capabilities & (1 <<1 )) {
403
426
_target_velocity_ned.x = packet.vel [0 ]; // velocity north
@@ -436,6 +459,12 @@ void AP_Follow::Log_Write_FOLL()
436
459
Vector3f vel_estimate;
437
460
UNUSED_RESULT (get_target_location_and_velocity (loc_estimate, vel_estimate));
438
461
462
+ Location _target_location;
463
+ UNUSED_RESULT (AP::ahrs ().get_location_from_origin_offset (_target_location, _target_position_ned * 0.01 ));
464
+ if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
465
+ _target_location.change_alt_frame (Location::AltFrame::ABOVE_HOME);
466
+ }
467
+
439
468
// log lead's estimated vs reported position
440
469
// @LoggerMessage: FOLL
441
470
// @Description: Follow library diagnostic data
@@ -536,17 +565,40 @@ void AP_Follow::clear_dist_and_bearing_to_target()
536
565
_bearing_to_target = 0 .0f ;
537
566
}
538
567
568
+ // get target's estimated origin-relative-position and velocity (both
569
+ // in SI NED), with offsets added
570
+ bool AP_Follow::get_target_position_and_velocity_ofs (Vector3p &pos_ned, Vector3f &vel_ned) const
571
+ {
572
+ Vector3f ofs_ned;
573
+ if (!get_offsets_ned (ofs_ned)) {
574
+ return false ;
575
+ }
576
+ if (!get_target_position_and_velocity_ofs (pos_ned, vel_ned)) {
577
+ return false ;
578
+ }
579
+ // can't add Vector3p and Vector3f directly:
580
+ pos_ned.x += ofs_ned.x ;
581
+ pos_ned.y += ofs_ned.y ;
582
+ pos_ned.z += ofs_ned.z ;
583
+ return true ;
584
+ }
585
+
539
586
// get target's estimated location and velocity (in NED), with offsets added
540
587
bool AP_Follow::get_target_location_and_velocity_ofs (Location &loc, Vector3f &vel_ned) const
541
588
{
542
- Vector3f ofs ;
543
- if (! get_offsets_ned (ofs) ||
544
- ! get_target_location_and_velocity (loc, vel_ned )) {
589
+ Vector3p pos_ned ;
590
+ Vector3f local_vel_ned; // so we either change both return parameters or neither
591
+ if (! get_target_position_and_velocity_ofs (pos_ned, local_vel_ned )) {
545
592
return false ;
546
593
}
547
- // apply offsets
548
- loc.offset (ofs.x , ofs.y );
549
- loc.alt -= ofs.z *100 ;
594
+ if (!AP::ahrs ().get_location_from_origin_offset (loc, pos_ned * 0.01 )) {
595
+ return false ;
596
+ }
597
+ if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {
598
+ loc.change_alt_frame (Location::AltFrame::ABOVE_HOME);
599
+ }
600
+
601
+ vel_ned = local_vel_ned;
550
602
return true ;
551
603
}
552
604
0 commit comments