Skip to content

Commit

Permalink
working
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 13, 2024
1 parent 728e63b commit be6bbc3
Show file tree
Hide file tree
Showing 76 changed files with 311 additions and 324 deletions.
6 changes: 3 additions & 3 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -629,9 +629,9 @@
#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED
#endif

#ifndef AC_PAYLOAD_PLACE_ENABLED
#define AC_PAYLOAD_PLACE_ENABLED 1
#endif




#ifndef USER_PARAMS_ENABLED
#define USER_PARAMS_ENABLED DISABLED
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ Mode::Mode(void) :
G_Dt(copter.G_Dt)
{ };

#if AC_PAYLOAD_PLACE_ENABLED

PayloadPlace Mode::payload_place;
#endif


// return the static controller object corresponding to supplied mode
Mode *Copter::mode_from_mode_num(const Mode::Number mode)
Expand Down
12 changes: 6 additions & 6 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class _AutoTakeoff {
Vector3p complete_pos; // target takeoff position as offset from ekf origin in cm
};

#if AC_PAYLOAD_PLACE_ENABLED

class PayloadPlace {
public:
void run();
Expand Down Expand Up @@ -60,7 +60,7 @@ class PayloadPlace {
float descent_start_altitude_cm;
float descent_speed_cms;
};
#endif


class Mode {
friend class PayloadPlace;
Expand Down Expand Up @@ -208,10 +208,10 @@ class Mode {
land_run_vertical_control(pause_descent);
}

#if AC_PAYLOAD_PLACE_ENABLED

// payload place flight behaviour:
static PayloadPlace payload_place;
#endif


// run normal or precision landing (if enabled)
// pause_descent is true if vehicle should not descend
Expand Down Expand Up @@ -510,9 +510,9 @@ class ModeAuto : public Mode {
NAVGUIDED,
LOITER,
LOITER_TO_ALT,
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED

NAV_PAYLOAD_PLACE,
#endif

NAV_SCRIPT_TIME,
NAV_ATTITUDE_TIME,
};
Expand Down
32 changes: 16 additions & 16 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,11 +152,11 @@ void ModeAuto::run()
loiter_to_alt_run();
break;

#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED

case SubMode::NAV_PAYLOAD_PLACE:
payload_place.run();
break;
#endif


case SubMode::NAV_ATTITUDE_TIME:
nav_attitude_time_run();
Expand Down Expand Up @@ -557,7 +557,7 @@ bool ModeAuto::is_taking_off() const
return ((_mode == SubMode::TAKEOFF) && !auto_takeoff.complete);
}

#if AC_PAYLOAD_PLACE_ENABLED

// auto_payload_place_start - initialises controller to implement a placing
void PayloadPlace::start_descent()
{
Expand Down Expand Up @@ -587,7 +587,7 @@ void PayloadPlace::start_descent()

state = PayloadPlace::State::Descent_Start;
}
#endif


// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeAuto::use_pilot_yaw(void) const
Expand Down Expand Up @@ -682,11 +682,11 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
do_nav_delay(cmd);
break;

#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED

case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint
do_payload_place(cmd);
break;
#endif



case MAV_CMD_NAV_SCRIPT_TIME:
Expand Down Expand Up @@ -892,11 +892,11 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
cmd_complete = verify_land();
break;

#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED

case MAV_CMD_NAV_PAYLOAD_PLACE:
cmd_complete = payload_place.verify();
break;
#endif


case MAV_CMD_NAV_LOITER_UNLIM:
cmd_complete = verify_loiter_unlimited();
Expand Down Expand Up @@ -1187,7 +1187,7 @@ void ModeAuto::nav_attitude_time_run()
pos_control->update_z_controller();
}

#if AC_PAYLOAD_PLACE_ENABLED

// auto_payload_place_run - places an object in auto mode
// called by auto_run at 100hz or more
void PayloadPlace::run()
Expand Down Expand Up @@ -1413,7 +1413,7 @@ void PayloadPlace::run()
break;
}
}
#endif


// sets the target_loc's alt to the vehicle's current alt but does not change target_loc's frame
// in the case of terrain altitudes either the terrain database or the rangefinder may be used
Expand Down Expand Up @@ -1535,9 +1535,9 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const
switch (next_cmd.id) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_NAV_LOITER_UNLIM:
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED

case MAV_CMD_NAV_PAYLOAD_PLACE:
#endif

case MAV_CMD_NAV_LOITER_TIME: {
const Location dest_loc = loc_from_cmd(current_cmd, default_loc);
const Location next_dest_loc = loc_from_cmd(next_cmd, dest_loc);
Expand Down Expand Up @@ -1944,7 +1944,7 @@ void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
}


#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED

// do_payload_place - initiate placing procedure
void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd)
{
Expand Down Expand Up @@ -1976,7 +1976,7 @@ void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd)
// set submode
set_submode(SubMode::NAV_PAYLOAD_PLACE);
}
#endif // AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED


// do_RTL - start Return-to-Launch
void ModeAuto::do_RTL(void)
Expand Down Expand Up @@ -2046,7 +2046,7 @@ bool ModeAuto::verify_land()
return retval;
}

#if AC_PAYLOAD_PLACE_ENABLED

// verify_payload_place - returns true if placing has been completed
bool PayloadPlace::verify()
{
Expand All @@ -2066,7 +2066,7 @@ bool PayloadPlace::verify()
// should never get here
return true;
}
#endif


bool ModeAuto::verify_loiter_unlimited()
{
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {

SCHED_TASK_CLASS(AP_RPM, &plane.rpm_sensor, update, 10, 100, 99),

#if AP_AIRSPEED_AUTOCAL_ENABLE

SCHED_TASK(airspeed_ratio_update, 1, 100, 102),
#endif // AP_AIRSPEED_AUTOCAL_ENABLE

#if HAL_MOUNT_ENABLED
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100, 105),
#endif // HAL_MOUNT_ENABLED
Expand Down Expand Up @@ -396,7 +396,7 @@ void Plane::compass_save()
}
}

#if AP_AIRSPEED_AUTOCAL_ENABLE

/*
once a second update the airspeed calibration ratio
*/
Expand Down Expand Up @@ -425,7 +425,7 @@ void Plane::airspeed_ratio_update(void)
const Vector3f &vg = gps.velocity();
airspeed.update_calibration(vg, aparm.airspeed_max);
}
#endif // AP_AIRSPEED_AUTOCAL_ENABLE


/*
read the GPS and update position
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Bootloader/AP_Bootloader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ int main(void)
try_boot = false;
timeout = 0;
}
#if AP_CHECK_FIRMWARE_ENABLED

const auto ok = check_good_firmware();
if (ok != check_fw_result_t::CHECK_FW_OK) {
// bad firmware CRC, don't try and boot
Expand All @@ -146,7 +146,7 @@ int main(void)
network.status_printf("Firmware Error: %d\n", (int)ok);
}
#endif
#endif // AP_CHECK_FIRMWARE_ENABLED

#ifndef BOOTLOADER_DEV_LIST
else if (timeout == HAL_BOOTLOADER_TIMEOUT) {
// fast boot for good firmware if we haven't been told to stay
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Bootloader/bl_protocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,14 +249,14 @@ jump_to_app()
{
const uint32_t *app_base = (const uint32_t *)(APP_START_ADDRESS);

#if AP_CHECK_FIRMWARE_ENABLED

const auto ok = check_good_firmware();
if (ok != check_fw_result_t::CHECK_FW_OK) {
// bad firmware, don't try and boot
led_set(LED_BAD_FW);
return;
}
#endif


// If we have QSPI chip start it
#if EXT_FLASH_SIZE_MB
Expand Down
16 changes: 8 additions & 8 deletions libraries/AP_Airspeed/AP_Airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,9 +261,9 @@ void AP_Airspeed::convert_per_instance()
{ {138, 842}, AP_PARAM_FLOAT, "OFFSET" }, // ARSPD_OFFSET, ARSPD2_OFFSET
{ {202, 906}, AP_PARAM_FLOAT, "RATIO" }, // ARSPD_RATIO, ARSPD2_RATIO
{ {266, 970}, AP_PARAM_INT8, "PIN" }, // ARSPD_PIN, ARSPD2_PIN
#if AP_AIRSPEED_AUTOCAL_ENABLE

{ {330, 1034}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL
#endif

{ {394, 1098}, AP_PARAM_INT8, "TUBE_ORDR" }, // ARSPD_TUBE_ORDER, ARSPD2_TUBE_ORDR
{ {458, 1162}, AP_PARAM_INT8, "SKIP_CAL" }, // ARSPD_SKIP_CAL, ARSPD2_SKIP_CAL
{ {522, 1226}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE
Expand All @@ -282,9 +282,9 @@ void AP_Airspeed::convert_per_instance()
const char* name;
} conversion_table[] = {
{ {0, 11}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE
#if AP_AIRSPEED_AUTOCAL_ENABLE

{ {5, 16}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL
#endif

{ {8, 19}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE
{ {24, 25}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID
};
Expand Down Expand Up @@ -342,10 +342,10 @@ void AP_Airspeed::allocate()
#else
// look for sensors based on type parameters
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
#if AP_AIRSPEED_AUTOCAL_ENABLE

state[i].calibration.init(param[i].ratio);
state[i].last_saved_ratio = param[i].ratio;
#endif


// Set the enable automatically to false and set the probability that the airspeed is healhy to start with
state[i].failures.health_probability = 1.0f;
Expand Down Expand Up @@ -425,11 +425,11 @@ void AP_Airspeed::allocate()
#endif
break;
case TYPE_NMEA_WATER:
#if AP_AIRSPEED_NMEA_ENABLED

#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
sensor[i] = new AP_Airspeed_NMEA(*this, i);
#endif
#endif

break;
case TYPE_MSP:
#if AP_AIRSPEED_MSP_ENABLED
Expand Down
12 changes: 6 additions & 6 deletions libraries/AP_Airspeed/AP_Airspeed.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ class AP_Airspeed_Params {
#endif
AP_Int8 type;
AP_Int8 bus;
#if AP_AIRSPEED_AUTOCAL_ENABLE

AP_Int8 autocal;
#endif


static const struct AP_Param::GroupInfo var_info[];
};
Expand Down Expand Up @@ -83,10 +83,10 @@ class AP_Airspeed
// indicate which bit in LOG_BITMASK indicates we should log airspeed readings
void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }

#if AP_AIRSPEED_AUTOCAL_ENABLE

// inflight ratio calibration
void set_calibration_enabled(bool enable) {calibration_enabled = enable;}
#endif //AP_AIRSPEED_AUTOCAL_ENABLE


// read the analog source and update airspeed
void update(void);
Expand Down Expand Up @@ -261,11 +261,11 @@ class AP_Airspeed
uint16_t read_count;
} cal;

#if AP_AIRSPEED_AUTOCAL_ENABLE

Airspeed_Calibration calibration;
float last_saved_ratio;
uint8_t counter;
#endif // AP_AIRSPEED_AUTOCAL_ENABLE


struct {
uint32_t last_check_ms;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include "AP_Airspeed_NMEA.h"

#if AP_AIRSPEED_NMEA_ENABLED


#include <AP_Vehicle/AP_Vehicle_Type.h>
#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
Expand Down Expand Up @@ -219,4 +219,4 @@ bool AP_Airspeed_NMEA::decode_latest_term()

#endif // APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)

#endif // AP_AIRSPEED_NMEA_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Airspeed/AP_Airspeed_NMEA.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include "AP_Airspeed_config.h"

#if AP_AIRSPEED_NMEA_ENABLED


#include "AP_Airspeed_Backend.h"
#include <AP_HAL/AP_HAL.h>
Expand Down Expand Up @@ -70,4 +70,4 @@ class AP_Airspeed_NMEA : public AP_Airspeed_Backend
uint32_t _last_update_ms;
};

#endif // AP_AIRSPEED_NMEA_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Airspeed/AP_Airspeed_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,14 +80,14 @@ const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = {
AP_GROUPINFO("PIN", 5, AP_Airspeed_Params, pin, 0),
#endif // HAL_BUILD_AP_PERIPH

#if AP_AIRSPEED_AUTOCAL_ENABLE

// @Param: AUTOCAL
// @DisplayName: Automatic airspeed ratio calibration
// @DisplayName{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
// @Description: Enables automatic adjustment of airspeed ratio during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.
// @User: Advanced
AP_GROUPINFO("AUTOCAL", 6, AP_Airspeed_Params, autocal, 0),
#endif


#ifndef HAL_BUILD_AP_PERIPH
// @Param: TUBE_ORDR
Expand Down
Loading

0 comments on commit be6bbc3

Please sign in to comment.