Skip to content

Commit

Permalink
hwdef.dat:New hardware description file added for BetaflightF4 target
Browse files Browse the repository at this point in the history
  • Loading branch information
Srivenkateshwar committed Nov 17, 2024
2 parents 7816a20 + 62565e6 commit 7783e91
Show file tree
Hide file tree
Showing 187 changed files with 3,744 additions and 607 deletions.
51 changes: 49 additions & 2 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,10 +276,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_NAV_CONTROLLER_OUTPUT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
};
Expand Down Expand Up @@ -315,7 +321,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
MSG_BATTERY_STATUS,
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};

const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
Expand Down Expand Up @@ -643,3 +650,43 @@ void GCS_MAVLINK_Tracker::send_global_position_int()
0, // Z speed cm/s (+ve Down)
tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree
}

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&tracker.mode_manual,
&tracker.mode_stop,
&tracker.mode_scan,
&tracker.mode_guided,
&tracker.mode_servotest,
&tracker.mode_auto,
&tracker.mode_initialising,
};

const uint8_t mode_count = ARRAY_SIZE(modes);

// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}

// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();

mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);

return mode_count;
}
4 changes: 4 additions & 0 deletions AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
void send_nav_controller_output() const override;
void send_pid_tuning() override;

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;

private:

void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
Expand Down
424 changes: 424 additions & 0 deletions AntennaTracker/ReleaseNotes.txt

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ void Tracker::one_second_loop()
mavlink_system.sysid = g.sysid_this_mav;

// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();

// updated armed/disarmed status LEDs
update_armed_disarmed();
Expand Down
8 changes: 8 additions & 0 deletions AntennaTracker/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ class Mode {

// returns a unique number specific to this mode
virtual Mode::Number number() const = 0;
virtual const char* name() const = 0;

virtual bool requires_armed_servos() const = 0;

Expand All @@ -41,13 +42,15 @@ class Mode {
class ModeAuto : public Mode {
public:
Mode::Number number() const override { return Mode::Number::AUTO; }
const char* name() const override { return "Auto"; }
bool requires_armed_servos() const override { return true; }
void update() override;
};

class ModeGuided : public Mode {
public:
Mode::Number number() const override { return Mode::Number::GUIDED; }
const char* name() const override { return "Guided"; }
bool requires_armed_servos() const override { return true; }
void update() override;

Expand All @@ -66,27 +69,31 @@ class ModeGuided : public Mode {
class ModeInitialising : public Mode {
public:
Mode::Number number() const override { return Mode::Number::INITIALISING; }
const char* name() const override { return "Initialising"; }
bool requires_armed_servos() const override { return false; }
void update() override {};
};

class ModeManual : public Mode {
public:
Mode::Number number() const override { return Mode::Number::MANUAL; }
const char* name() const override { return "Manual"; }
bool requires_armed_servos() const override { return true; }
void update() override;
};

class ModeScan : public Mode {
public:
Mode::Number number() const override { return Mode::Number::SCAN; }
const char* name() const override { return "Scan"; }
bool requires_armed_servos() const override { return true; }
void update() override;
};

class ModeServoTest : public Mode {
public:
Mode::Number number() const override { return Mode::Number::SERVOTEST; }
const char* name() const override { return "ServoTest"; }
bool requires_armed_servos() const override { return true; }
void update() override {};

Expand All @@ -96,6 +103,7 @@ class ModeServoTest : public Mode {
class ModeStop : public Mode {
public:
Mode::Number number() const override { return Mode::Number::STOP; }
const char* name() const override { return "Stop"; }
bool requires_armed_servos() const override { return false; }
void update() override {};
};
2 changes: 1 addition & 1 deletion AntennaTracker/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
void Tracker::init_servos()
{
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();

SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw);
SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
// features below are disabled by default on all boards
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
//#define ADVANCED_FAILSAFE 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events
//#define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events

// other settings
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "Copter.h"

#pragma GCC diagnostic push
#if defined(__clang__)
#if defined(__clang_major__) && __clang_major__ >= 14
#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"
#endif

Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if HAL_ADSB_ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100, 138),
#endif
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
SCHED_TASK(afs_fs_check, 10, 100, 141),
#endif
#if AP_TERRAIN_AVAILABLE
Expand Down Expand Up @@ -727,7 +727,7 @@ void Copter::one_hz_loop()
}

// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();

#if HAL_LOGGING_ENABLED
// log terrain data
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@
#include <AP_OSD/AP_OSD.h>
#endif

#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
# include "afs_copter.h"
#endif
#if TOY_MODE_ENABLED
Expand Down Expand Up @@ -183,7 +183,7 @@ class Copter : public AP_Vehicle {
friend class ParametersG2;
friend class AP_Avoidance_Copter;

#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
friend class AP_AdvancedFailsafe_Copter;
#endif
friend class AP_Arming_Copter;
Expand Down Expand Up @@ -804,7 +804,7 @@ class Copter : public AP_Vehicle {
// failsafe.cpp
void failsafe_enable();
void failsafe_disable();
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
void afs_fs_check(void);
#endif

Expand Down
130 changes: 127 additions & 3 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -505,10 +505,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
Expand Down Expand Up @@ -583,7 +589,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
static const ap_message STREAM_ADSB_msgs[] = {
MSG_ADSB_VEHICLE,
Expand Down Expand Up @@ -1519,7 +1526,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
}

MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {
return MAV_RESULT_ACCEPTED;
}
Expand Down Expand Up @@ -1657,3 +1664,120 @@ uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
#if MODE_AUTO_ENABLED
&copter.mode_auto, // This auto is actually auto RTL!
&copter.mode_auto, // This one is really is auto!
#endif
#if MODE_ACRO_ENABLED
&copter.mode_acro,
#endif
&copter.mode_stabilize,
&copter.mode_althold,
#if MODE_CIRCLE_ENABLED
&copter.mode_circle,
#endif
#if MODE_LOITER_ENABLED
&copter.mode_loiter,
#endif
#if MODE_GUIDED_ENABLED
&copter.mode_guided,
#endif
&copter.mode_land,
#if MODE_RTL_ENABLED
&copter.mode_rtl,
#endif
#if MODE_DRIFT_ENABLED
&copter.mode_drift,
#endif
#if MODE_SPORT_ENABLED
&copter.mode_sport,
#endif
#if MODE_FLIP_ENABLED
&copter.mode_flip,
#endif
#if AUTOTUNE_ENABLED
&copter.mode_autotune,
#endif
#if MODE_POSHOLD_ENABLED
&copter.mode_poshold,
#endif
#if MODE_BRAKE_ENABLED
&copter.mode_brake,
#endif
#if MODE_THROW_ENABLED
&copter.mode_throw,
#endif
#if HAL_ADSB_ENABLED
&copter.mode_avoid_adsb,
#endif
#if MODE_GUIDED_NOGPS_ENABLED
&copter.mode_guided_nogps,
#endif
#if MODE_SMARTRTL_ENABLED
&copter.mode_smartrtl,
#endif
#if MODE_FLOWHOLD_ENABLED
(Mode*)copter.g2.mode_flowhold_ptr,
#endif
#if MODE_FOLLOW_ENABLED
&copter.mode_follow,
#endif
#if MODE_ZIGZAG_ENABLED
&copter.mode_zigzag,
#endif
#if MODE_SYSTEMID_ENABLED
(Mode *)copter.g2.mode_systemid_ptr,
#endif
#if MODE_AUTOROTATE_ENABLED
&copter.mode_autorotate,
#endif
#if MODE_TURTLE_ENABLED
&copter.mode_turtle,
#endif
};

const uint8_t mode_count = ARRAY_SIZE(modes);

// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}

// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
uint8_t mode_number = (uint8_t)modes[index_zero]->mode_number();

#if MODE_AUTO_ENABLED
// Auto RTL is odd
// Have to deal with is separately becase its number and name can change depending on if were in it or not
if (index_zero == 0) {
mode_number = (uint8_t)Mode::Number::AUTO_RTL;
name = "AUTO RTL";

} else if (index_zero == 1) {
mode_number = (uint8_t)Mode::Number::AUTO;
name = "AUTO";

}
#endif

mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);

return mode_count;
}
4 changes: 4 additions & 0 deletions ArduCopter/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,10 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
#endif

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;

private:

// sanity check velocity or acceleration vector components are numbers
Expand Down
Loading

0 comments on commit 7783e91

Please sign in to comment.