Plane: link in AP_Follow

ready for ship landing
This commit is contained in:
Andrew Tridgell 2022-01-04 15:53:18 +11:00
parent ab64744ccd
commit c54fb0f51b
5 changed files with 35 additions and 0 deletions

View File

@ -652,6 +652,10 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
{
#if HAL_ADSB_ENABLED
plane.avoidance_adsb.handle_msg(msg);
#endif
#if SHIP_LANDING_ENABLED
// pass message to follow library
plane.g2.follow.handle_msg(msg);
#endif
GCS_MAVLINK::packetReceived(status, msg);
}
@ -884,6 +888,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
case MAV_CMD_GUIDED_CHANGE_HEADING:
return handle_command_int_guided_slew_commands(packet);
case MAV_CMD_DO_FOLLOW:
#if SHIP_LANDING_ENABLED
// param1: sysid of target to follow
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
plane.g2.follow.set_target_sysid((uint8_t)packet.param1);
return MAV_RESULT_ACCEPTED;
}
#endif
return MAV_RESULT_FAILED;
default:
return GCS_MAVLINK::handle_command_int_packet(packet);
}
@ -1085,6 +1099,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
}
return MAV_RESULT_ACCEPTED;
#if SHIP_LANDING_ENABLED
case MAV_CMD_DO_FOLLOW:
// param1: sysid of target to follow
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
plane.g2.follow.set_target_sysid((uint8_t)packet.param1);
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
#endif
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
}

View File

@ -1229,6 +1229,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
// @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15
AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0),
#if SHIP_LANDING_ENABLED
// @Group: FOLL
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow),
#endif
AP_GROUPEND
};

View File

@ -545,6 +545,9 @@ public:
AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.2};
#endif
#if SHIP_LANDING_ENABLED
AP_Follow follow;
#endif
AP_Float fs_ekf_thresh;

View File

@ -82,6 +82,7 @@
#include <AP_Gripper/AP_Gripper.h>
#include <AP_Landing/AP_Landing.h>
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AP_Follow/AP_Follow.h>
#include "GCS_Mavlink.h"
#include "GCS_Plane.h"

View File

@ -29,6 +29,7 @@ def build(bld):
'AP_OSD',
'AC_AutoTune',
'AP_KDECAN',
'AP_Follow',
],
)