Skip to content

Commit

Permalink
working
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 8, 2024
1 parent 68b671d commit a7c64e0
Show file tree
Hide file tree
Showing 202 changed files with 1,006 additions and 1,182 deletions.
16 changes: 8 additions & 8 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
#endif // HELI_FRAME

// checks when using range finder for RTL
#if MODE_RTL_ENABLED == ENABLED

if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) {
// get terrain source from wpnav
const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";
Expand All @@ -272,7 +272,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
break;
}
}
#endif


// check adsb avoidance failsafe
#if HAL_ADSB_ENABLED
Expand Down Expand Up @@ -734,9 +734,9 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
copter.update_super_simple_bearing(false);

// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
#if MODE_SMARTRTL_ENABLED == ENABLED

copter.g2.smart_rtl.set_home(copter.position_ok());
#endif


hal.util->set_soft_armed(true);

Expand Down Expand Up @@ -814,14 +814,14 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
}
}

#if AUTOTUNE_ENABLED == ENABLED

// save auto tuned parameters
if (copter.flightmode == &copter.mode_autotune) {
copter.mode_autotune.save_tuning_gains();
} else {
copter.mode_autotune.reset();
}
#endif


// we are not in the air
copter.set_land_complete(true);
Expand All @@ -830,10 +830,10 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
// send disarm command to motors
copter.motors->armed(false);

#if MODE_AUTO_ENABLED == ENABLED

// reset the mission
copter.mode_auto.mission.reset();
#endif


#if HAL_LOGGING_ENABLED
AP::logger().set_vehicle_armed(false);
Expand Down
28 changes: 14 additions & 14 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,9 +164,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#endif
SCHED_TASK(auto_disarm_check, 10, 50, 27),
SCHED_TASK(auto_trim, 10, 75, 30),
#if RANGEFINDER_ENABLED == ENABLED

SCHED_TASK(read_rangefinder, 20, 100, 33),
#endif

#if HAL_PROXIMITY_ENABLED
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36),
#endif
Expand All @@ -176,9 +176,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(update_altitude, 10, 100, 42),
SCHED_TASK(run_nav_updates, 50, 100, 45),
SCHED_TASK(update_throttle_hover,100, 90, 48),
#if MODE_SMARTRTL_ENABLED == ENABLED

SCHED_TASK_CLASS(ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100, 51),
#endif

#if HAL_SPRAYER_ENABLED
SCHED_TASK_CLASS(AC_Sprayer, &copter.sprayer, update, 3, 90, 54),
#endif
Expand Down Expand Up @@ -274,7 +274,7 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
constexpr int8_t Copter::_failsafe_priorities[7];


#if MODE_GUIDED_ENABLED == ENABLED

// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
{
Expand Down Expand Up @@ -385,9 +385,9 @@ bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, flo
mode_guided.set_angle(q, Vector3f{}, climb_rate_ms*100, false);
return true;
}
#endif

#if MODE_CIRCLE_ENABLED == ENABLED


// circle mode controls
bool Copter::get_circle_radius(float &radius_m)
{
Expand All @@ -400,15 +400,15 @@ bool Copter::set_circle_rate(float rate_dps)
circle_nav->set_rate(rate_dps);
return true;
}
#endif


// set desired speed (m/s). Used for scripting.
bool Copter::set_desired_speed(float speed)
{
return flightmode->set_speed_xy(speed * 100.0f);
}

#if MODE_AUTO_ENABLED == ENABLED

// returns true if mode supports NAV_SCRIPT_TIME mission commands
bool Copter::nav_scripting_enable(uint8_t mode)
{
Expand All @@ -434,7 +434,7 @@ void Copter::nav_script_time_done(uint16_t id)

return mode_auto.nav_script_time_done(id);
}
#endif


// returns true if the EKF failsafe has triggered. Only used by Lua scripts
bool Copter::has_ekf_failsafed() const
Expand All @@ -458,11 +458,11 @@ bool Copter::is_taking_off() const

bool Copter::current_mode_requires_mission() const
{
#if MODE_AUTO_ENABLED == ENABLED

return flightmode == &mode_auto;
#else
return false;
#endif



}

// rc_loops - reads user input from transmitter/receiver
Expand Down
104 changes: 52 additions & 52 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,15 +114,15 @@
# include <AC_PrecLand/AC_PrecLand.h>
# include <AC_PrecLand/AC_PrecLand_StateMachine.h>

#if MODE_FOLLOW_ENABLED == ENABLED

# include <AP_Follow/AP_Follow.h>
#endif


# include <AP_Terrain/AP_Terrain.h>

#if RANGEFINDER_ENABLED == ENABLED

# include <AP_RangeFinder/AP_RangeFinder.h>
#endif


#include <AP_Mount/AP_Mount.h>

Expand Down Expand Up @@ -490,9 +490,9 @@ class Copter : public AP_Vehicle {
AC_CustomControl custom_control{ahrs_view, attitude_control, motors, scheduler.get_loop_period_s()};
#endif

#if MODE_CIRCLE_ENABLED == ENABLED

AC_Circle *circle_nav;
#endif


// System Timers
// --------------
Expand Down Expand Up @@ -528,9 +528,9 @@ class Copter : public AP_Vehicle {
#endif

// Parachute release
#if PARACHUTE == ENABLED

AP_Parachute parachute;
#endif


// Landing Gear Controller

Expand Down Expand Up @@ -667,7 +667,7 @@ class Copter : public AP_Vehicle {
uint8_t &task_count,
uint32_t &log_bit) override;

#if MODE_GUIDED_ENABLED == ENABLED

bool start_takeoff(float alt) override;
bool set_target_location(const Location& target_loc) override;
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override;
Expand All @@ -676,17 +676,17 @@ class Copter : public AP_Vehicle {
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
bool set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool relative_yaw) override;
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
#endif
#if MODE_CIRCLE_ENABLED == ENABLED


bool get_circle_radius(float &radius_m) override;
bool set_circle_rate(float rate_dps) override;
#endif

bool set_desired_speed(float speed) override;
#if MODE_AUTO_ENABLED == ENABLED

bool nav_scripting_enable(uint8_t mode) override;
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override;
void nav_script_time_done(uint16_t id) override;
#endif

// lua scripts use this to retrieve EKF failsafe state
// returns true if the EKF failsafe has triggered
bool has_ekf_failsafed() const override;
Expand Down Expand Up @@ -971,83 +971,83 @@ class Copter : public AP_Vehicle {
void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag);
void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag);

#if MODE_ACRO_ENABLED == ENABLED

#if FRAME_CONFIG == HELI_FRAME
ModeAcro_Heli mode_acro;
#else
ModeAcro mode_acro;
#endif
#endif

ModeAltHold mode_althold;
#if MODE_AUTO_ENABLED == ENABLED

ModeAuto mode_auto;
#endif
#if AUTOTUNE_ENABLED == ENABLED


ModeAutoTune mode_autotune;
#endif
#if MODE_BRAKE_ENABLED == ENABLED


ModeBrake mode_brake;
#endif
#if MODE_CIRCLE_ENABLED == ENABLED


ModeCircle mode_circle;
#endif
#if MODE_DRIFT_ENABLED == ENABLED


ModeDrift mode_drift;
#endif
#if MODE_FLIP_ENABLED == ENABLED


ModeFlip mode_flip;
#endif
#if MODE_FOLLOW_ENABLED == ENABLED


ModeFollow mode_follow;
#endif
#if MODE_GUIDED_ENABLED == ENABLED


ModeGuided mode_guided;
#endif

ModeLand mode_land;
#if MODE_LOITER_ENABLED == ENABLED

ModeLoiter mode_loiter;
#endif
#if MODE_POSHOLD_ENABLED == ENABLED


ModePosHold mode_poshold;
#endif
#if MODE_RTL_ENABLED == ENABLED


ModeRTL mode_rtl;
#endif

#if FRAME_CONFIG == HELI_FRAME
ModeStabilize_Heli mode_stabilize;
#else
ModeStabilize mode_stabilize;
#endif
#if MODE_SPORT_ENABLED == ENABLED

ModeSport mode_sport;
#endif

#if MODE_SYSTEMID_ENABLED == ENABLED
ModeSystemId mode_systemid;
#endif
#if HAL_ADSB_ENABLED
ModeAvoidADSB mode_avoid_adsb;
#endif
#if MODE_THROW_ENABLED == ENABLED

ModeThrow mode_throw;
#endif
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED


ModeGuidedNoGPS mode_guided_nogps;
#endif
#if MODE_SMARTRTL_ENABLED == ENABLED


ModeSmartRTL mode_smartrtl;
#endif
#if MODE_FLOWHOLD_ENABLED == ENABLED


ModeFlowHold mode_flowhold;
#endif
#if MODE_ZIGZAG_ENABLED == ENABLED


ModeZigZag mode_zigzag;
#endif

#if MODE_AUTOROTATE_ENABLED == ENABLED
ModeAutorotate mode_autorotate;
#endif
#if MODE_TURTLE_ENABLED == ENABLED

ModeTurtle mode_turtle;
#endif


// mode.cpp
Mode *mode_from_mode_num(const Mode::Number mode);
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/GCS_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif

#if RANGEFINDER_ENABLED == ENABLED

const RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
Expand All @@ -102,7 +102,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
}
}
#endif



if (copter.precland.enabled()) {
Expand Down
Loading

0 comments on commit a7c64e0

Please sign in to comment.