Skip to content

Commit

Permalink
Merge branch 'master' into pr-mlx90-sensor
Browse files Browse the repository at this point in the history
  • Loading branch information
rahulOCR authored Apr 26, 2024
2 parents 0bed8bb + 338f492 commit c40af01
Show file tree
Hide file tree
Showing 572 changed files with 23,810 additions and 3,942 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/test_ccache.yml
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,6 @@ jobs:
shell: bash
run: |
PATH="/usr/lib/ccache:/opt/gcc-arm-none-eabi-${{matrix.gcc}}/bin:$PATH"
Tools/scripts/build_tests/test_ccache.py --boards MatekF405,MatekF405-bdshot --min-cache-pct=75
Tools/scripts/build_tests/test_ccache.py --boards Durandal,Pixhawk6X --min-cache-pct=70
Tools/scripts/build_tests/test_ccache.py --boards MatekF405-bdshot,MatekF405-TE-bdshot --min-cache-pct=75
Tools/scripts/build_tests/test_ccache.py --boards Durandal-bdshot,Pixhawk6X --min-cache-pct=70
9 changes: 1 addition & 8 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,13 +451,6 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_
}
}

bool GCS_MAVLINK_Tracker::set_home_to_current_location(bool _lock) {
return tracker.set_home(AP::gps().location());
}
bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool _lock) {
return tracker.set_home(loc);
}

void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg)
{
switch (msg.msgid) {
Expand Down Expand Up @@ -584,7 +577,7 @@ void GCS_MAVLINK_Tracker::handle_message_mission_item(const mavlink_message_t &m

// check if this is the HOME wp
if (packet.seq == 0) {
if (!tracker.set_home(tell_command)) {
if (!tracker.set_home(tell_command, false)) {
result = MAV_MISSION_ERROR;
goto mission_failed;
}
Expand Down
3 changes: 0 additions & 3 deletions AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,6 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
return 0; // what if we have been picked up and carried somewhere?
}

bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;

void send_nav_controller_output() const override;
void send_pid_tuning() override;

Expand Down
15 changes: 15 additions & 0 deletions AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,19 @@
Antenna Tracker Release Notes:

------------------------------------------------------------------
Release 4.5.1 8th April 2024

This release fixes a critical bug in the CRSF R/C protocol parser that
can lead to a handfault and a vehicle crashing. A similar fix was
applied to the GHST protocol, although we believe that GHST could not
be affected by the bug, so this was just a precaution.

There are no other changes in this release.

------------------------------------------------------------------
Release 4.5.0 2nd April 2024

No changes from 4.5.0-beta4
------------------------------------------------------------------
Release 4.5.0-beta4 22nd March 2024
Changes from 4.5.0-beta3
Expand Down
3 changes: 1 addition & 2 deletions AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50),
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900, 55),
#if HAL_LOGGING_ENABLED
SCHED_TASK(ten_hz_logging_loop, 10, 300, 60),
SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65),
Expand Down Expand Up @@ -92,7 +91,7 @@ void Tracker::one_second_loop()
// set home to current location
Location temp_loc;
if (ahrs.get_location(temp_loc)) {
if (!set_home(temp_loc)){
if (!set_home(temp_loc, false)) {
// fail silently
}
}
Expand Down
3 changes: 2 additions & 1 deletion AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,8 @@ class Tracker : public AP_Vehicle {
void init_ardupilot() override;
bool get_home_eeprom(Location &loc) const;
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
bool set_home(const Location &temp) WARN_IF_UNUSED;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location &temp, bool lock) override WARN_IF_UNUSED;
void prepare_servos();
void set_mode(Mode &newmode, ModeReason reason);
bool set_mode(uint8_t new_mode, ModeReason reason) override;
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void Tracker::update_GPS(void)
// Now have an initial GPS position
// use it as the HOME position in future startups
current_loc = gps.location();
IGNORE_RETURN(set_home(current_loc));
IGNORE_RETURN(set_home(current_loc, false));
ground_start_count = 0;
}
}
Expand Down
7 changes: 6 additions & 1 deletion AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,12 @@ bool Tracker::set_home_eeprom(const Location &temp)
return true;
}

bool Tracker::set_home(const Location &temp)
bool Tracker::set_home_to_current_location(bool lock)
{
return set_home(AP::gps().location(), lock);
}

bool Tracker::set_home(const Location &temp, bool lock)
{
// check EKF origin has been set
Location ekf_origin;
Expand Down
6 changes: 1 addition & 5 deletions AntennaTracker/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,7 @@ def build(bld):
bld.ap_stlib(
name=vehicle + '_libs',
ap_vehicle=vehicle,
ap_libraries=bld.ap_common_vehicle_libraries() + [
'AP_Beacon',
'AP_Arming',
'AP_RCMapper',
],
ap_libraries=bld.ap_common_vehicle_libraries(),
)

bld.ap_program(
Expand Down
12 changes: 0 additions & 12 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -495,18 +495,6 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
}
}

// check if home is too far from EKF origin
if (copter.far_from_EKF_origin(ahrs.get_home())) {
check_failed(display_failure, "Home too far from EKF origin");
return false;
}

// check if vehicle is too far from EKF origin
if (copter.far_from_EKF_origin(copter.current_loc)) {
check_failed(display_failure, "Vehicle too far from EKF origin");
return false;
}

// if we got here all must be ok
return true;
}
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if AP_SERVORELAYEVENTS_ENABLED
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),
#endif
SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63),
#if AC_PRECLAND_ENABLED
SCHED_TASK(update_precland, 400, 50, 69),
#endif
Expand Down
5 changes: 2 additions & 3 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -739,9 +739,8 @@ class Copter : public AP_Vehicle {
// commands.cpp
void update_home_from_EKF();
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
bool far_from_EKF_origin(const Location& loc);
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;

// compassmot.cpp
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);
Expand Down
83 changes: 39 additions & 44 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -711,13 +711,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int
return GCS_MAVLINK::handle_preflight_reboot(packet, msg);
}

bool GCS_MAVLINK_Copter::set_home_to_current_location(bool _lock) {
return copter.set_home_to_current_location(_lock);
}
bool GCS_MAVLINK_Copter::set_home(const Location& loc, bool _lock) {
return copter.set_home(loc, _lock);
}

MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
{
#if MODE_GUIDED_ENABLED == ENABLED
Expand Down Expand Up @@ -1169,8 +1162,6 @@ bool GCS_MAVLINK_Copter::sane_vel_or_acc_vector(const Vector3f &vec) const
return true;
}

void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
{
#if MODE_GUIDED_ENABLED == ENABLED
// for mavlink SET_POSITION_TARGET messages
constexpr uint32_t MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE =
Expand All @@ -1196,18 +1187,16 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
POSITION_TARGET_TYPEMASK_FORCE_SET;
#endif

switch (msg.msgid) {

#if MODE_GUIDED_ENABLED == ENABLED
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: // MAV ID: 82
{
void GCS_MAVLINK_Copter::handle_message_set_attitude_target(const mavlink_message_t &msg)
{
// decode packet
mavlink_set_attitude_target_t packet;
mavlink_msg_set_attitude_target_decode(&msg, &packet);

// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!copter.flightmode->in_guided_mode()) {
break;
return;
}

const bool roll_rate_ignore = packet.type_mask & ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
Expand All @@ -1218,7 +1207,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)

// ensure thrust field is not ignored
if (throttle_ignore) {
break;
return;
}

Quaternion attitude_quat;
Expand All @@ -1232,7 +1221,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
// this limit is somewhat greater than sqrt(FLT_EPSL)
if (!attitude_quat.is_unit_length()) {
// The attitude quaternion is ill-defined
break;
return;
}
}

Expand Down Expand Up @@ -1270,19 +1259,17 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)

copter.mode_guided.set_angle(attitude_quat, ang_vel,
climb_rate_or_thrust, use_thrust);
}

break;
}

case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: // MAV ID: 84
{
void GCS_MAVLINK_Copter::handle_message_set_position_target_local_ned(const mavlink_message_t &msg)
{
// decode packet
mavlink_set_position_target_local_ned_t packet;
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);

// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!copter.flightmode->in_guided_mode()) {
break;
return;
}

// check for supported coordinate frames
Expand All @@ -1292,7 +1279,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
// input is not valid so stop
copter.mode_guided.init(true);
break;
return;
}

bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
Expand All @@ -1305,7 +1292,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
// Force inputs are not supported
// Do not accept command if force_set is true and acc_ignore is false
if (force_set && !acc_ignore) {
break;
return;
}

// prepare position
Expand Down Expand Up @@ -1378,19 +1365,17 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
// input is not valid so stop
copter.mode_guided.init(true);
}
}

break;
}

case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: // MAV ID: 86
{
void GCS_MAVLINK_Copter::handle_message_set_position_target_global_int(const mavlink_message_t &msg)
{
// decode packet
mavlink_set_position_target_global_int_t packet;
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);

// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!copter.flightmode->in_guided_mode()) {
break;
return;
}

// todo: do we need to check for supported coordinate frames
Expand All @@ -1405,7 +1390,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
// Force inputs are not supported
// Do not accept command if force_set is true and acc_ignore is false
if (force_set && !acc_ignore) {
break;
return;
}

// extract location from message
Expand All @@ -1415,14 +1400,14 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
if (!check_latlng(packet.lat_int, packet.lon_int)) {
// input is not valid so stop
copter.mode_guided.init(true);
break;
return;
}
Location::AltFrame frame;
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.coordinate_frame, frame)) {
// unknown coordinate frame
// input is not valid so stop
copter.mode_guided.init(true);
break;
return;
}
loc = {packet.lat_int, packet.lon_int, int32_t(packet.alt*100), frame};
}
Expand Down Expand Up @@ -1463,13 +1448,13 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
// posvel controller does not support alt-above-terrain
// input is not valid so stop
copter.mode_guided.init(true);
break;
return;
}
Vector3f pos_neu_cm;
if (!loc.get_vector_from_origin_NEU(pos_neu_cm)) {
// input is not valid so stop
copter.mode_guided.init(true);
break;
return;
}
copter.mode_guided.set_destination_posvel(pos_neu_cm, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds);
} else if (pos_ignore && !vel_ignore) {
Expand All @@ -1482,30 +1467,40 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
// input is not valid so stop
copter.mode_guided.init(true);
}
}
#endif // MODE_GUIDED_ENABLED == ENABLED

void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
{

switch (msg.msgid) {
#if MODE_GUIDED_ENABLED == ENABLED
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
handle_message_set_attitude_target(msg);
break;
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
handle_message_set_position_target_local_ned(msg);
break;
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
handle_message_set_position_target_global_int(msg);
break;
}
#endif

#if AP_TERRAIN_AVAILABLE
case MAVLINK_MSG_ID_TERRAIN_DATA:
case MAVLINK_MSG_ID_TERRAIN_CHECK:
#if AP_TERRAIN_AVAILABLE
copter.terrain.handle_data(chan, msg);
#endif
break;

#endif
#if TOY_MODE_ENABLED == ENABLED
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
copter.g2.toy_mode.handle_message(msg);
break;
#endif

default:
GCS_MAVLINK::handle_message(msg);
break;
} // end switch
} // end handle mavlink

}
}

MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {
#if ADVANCED_FAILSAFE == ENABLED
Expand Down
6 changes: 4 additions & 2 deletions ArduCopter/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,12 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK
void handle_mount_message(const mavlink_message_t &msg) override;
#endif

void handle_message_set_attitude_target(const mavlink_message_t &msg);
void handle_message_set_position_target_global_int(const mavlink_message_t &msg);
void handle_message_set_position_target_local_ned(const mavlink_message_t &msg);

void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;

bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
void send_nav_controller_output() const override;
uint64_t capabilities() const override;

Expand Down
Loading

0 comments on commit c40af01

Please sign in to comment.