Skip to content

Commit

Permalink
Copter: rename flightmode_ objects to mode_
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Dec 12, 2017
1 parent c3fbf26 commit 2d23e1f
Show file tree
Hide file tree
Showing 16 changed files with 109 additions and 109 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/ArduCopter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -537,7 +537,7 @@ void Copter::update_GPS(void)

void Copter::smart_rtl_save_position()
{
flightmode_smartrtl.save_position();
mode_smartrtl.save_position();
}

void Copter::init_simple_bearing()
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Copter::Copter(void)
auto_trim_counter(0),
in_mavlink_delay(false),
param_loader(var_info),
flightmode(&flightmode_stabilize)
flightmode(&mode_stabilize)
{
memset(&current_loc, 0, sizeof(current_loc));

Expand Down
44 changes: 22 additions & 22 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -946,54 +946,54 @@ class Copter : public AP_HAL::HAL::Callbacks {
Copter::Mode *flightmode;

#if FRAME_CONFIG == HELI_FRAME
Copter::ModeAcro_Heli flightmode_acro{*this};
Copter::ModeAcro_Heli mode_acro{*this};
#else
Copter::ModeAcro flightmode_acro{*this};
Copter::ModeAcro mode_acro{*this};
#endif

Copter::ModeAltHold flightmode_althold{*this};
Copter::ModeAltHold mode_althold{*this};

Copter::ModeAuto flightmode_auto{*this, mission, circle_nav};
Copter::ModeAuto mode_auto{*this, mission, circle_nav};

#if AUTOTUNE_ENABLED == ENABLED
Copter::ModeAutoTune flightmode_autotune{*this};
Copter::ModeAutoTune mode_autotune{*this};
#endif

Copter::ModeBrake flightmode_brake{*this};
Copter::ModeBrake mode_brake{*this};

Copter::ModeCircle flightmode_circle{*this, circle_nav};
Copter::ModeCircle mode_circle{*this, circle_nav};

Copter::ModeDrift flightmode_drift{*this};
Copter::ModeDrift mode_drift{*this};

Copter::ModeFlip flightmode_flip{*this};
Copter::ModeFlip mode_flip{*this};

Copter::ModeGuided flightmode_guided{*this};
Copter::ModeGuided mode_guided{*this};

Copter::ModeLand flightmode_land{*this};
Copter::ModeLand mode_land{*this};

Copter::ModeLoiter flightmode_loiter{*this};
Copter::ModeLoiter mode_loiter{*this};

Copter::ModePosHold flightmode_poshold{*this};
Copter::ModePosHold mode_poshold{*this};

Copter::ModeRTL flightmode_rtl{*this};
Copter::ModeRTL mode_rtl{*this};

#if FRAME_CONFIG == HELI_FRAME
Copter::ModeStabilize_Heli flightmode_stabilize{*this};
Copter::ModeStabilize_Heli mode_stabilize{*this};
#else
Copter::ModeStabilize flightmode_stabilize{*this};
Copter::ModeStabilize mode_stabilize{*this};
#endif

Copter::ModeSport flightmode_sport{*this};
Copter::ModeSport mode_sport{*this};

Copter::ModeAvoidADSB flightmode_avoid_adsb{*this};
Copter::ModeAvoidADSB mode_avoid_adsb{*this};

Copter::ModeThrow flightmode_throw{*this};
Copter::ModeThrow mode_throw{*this};

Copter::ModeGuidedNoGPS flightmode_guided_nogps{*this};
Copter::ModeGuidedNoGPS mode_guided_nogps{*this};

Copter::ModeSmartRTL flightmode_smartrtl{*this};
Copter::ModeSmartRTL mode_smartrtl{*this};

Copter::Mode *flightmode_for_mode(const uint8_t mode);
Copter::Mode *mode_from_mode_num(const uint8_t mode);

void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);

Expand Down
22 changes: 11 additions & 11 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1291,7 +1291,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)

if (!shot_mode) {
if (copter.set_mode(BRAKE, MODE_REASON_GCS_COMMAND)) {
copter.flightmode_brake.timeout_to_loiter_ms(2500);
copter.mode_brake.timeout_to_loiter_ms(2500);
} else {
copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND);
}
Expand Down Expand Up @@ -1335,7 +1335,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
mavlink_msg_set_attitude_target_decode(msg, &packet);

// exit if vehicle is not in Guided mode or Auto-Guided mode
if ((copter.control_mode != GUIDED) && (copter.control_mode != GUIDED_NOGPS) && !(copter.control_mode == AUTO && copter.flightmode_auto.mode() == Auto_NavGuided)) {
if ((copter.control_mode != GUIDED) && (copter.control_mode != GUIDED_NOGPS) && !(copter.control_mode == AUTO && copter.mode_auto.mode() == Auto_NavGuided)) {
break;
}

Expand Down Expand Up @@ -1364,7 +1364,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
use_yaw_rate = true;
}

copter.flightmode_guided.set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),
copter.mode_guided.set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),
climb_rate_cms, use_yaw_rate, packet.body_yaw_rate);

break;
Expand All @@ -1377,7 +1377,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
mavlink_msg_set_position_target_local_ned_decode(msg, &packet);

// exit if vehicle is not in Guided mode or Auto-Guided mode
if ((copter.control_mode != GUIDED) && !(copter.control_mode == AUTO && copter.flightmode_auto.mode() == Auto_NavGuided)) {
if ((copter.control_mode != GUIDED) && !(copter.control_mode == AUTO && copter.mode_auto.mode() == Auto_NavGuided)) {
break;
}

Expand Down Expand Up @@ -1446,16 +1446,16 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)

// send request
if (!pos_ignore && !vel_ignore && acc_ignore) {
if (copter.flightmode_guided.set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
if (copter.mode_guided.set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
} else if (pos_ignore && !vel_ignore && acc_ignore) {
copter.flightmode_guided.set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
copter.mode_guided.set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
result = MAV_RESULT_ACCEPTED;
} else if (!pos_ignore && vel_ignore && acc_ignore) {
if (copter.flightmode_guided.set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
if (copter.mode_guided.set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
Expand All @@ -1474,7 +1474,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
mavlink_msg_set_position_target_global_int_decode(msg, &packet);

// exit if vehicle is not in Guided mode or Auto-Guided mode
if ((copter.control_mode != GUIDED) && !(copter.control_mode == AUTO && copter.flightmode_auto.mode() == Auto_NavGuided)) {
if ((copter.control_mode != GUIDED) && !(copter.control_mode == AUTO && copter.mode_auto.mode() == Auto_NavGuided)) {
break;
}

Expand Down Expand Up @@ -1548,16 +1548,16 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
}

if (!pos_ignore && !vel_ignore && acc_ignore) {
if (copter.flightmode_guided.set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
if (copter.mode_guided.set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
} else if (pos_ignore && !vel_ignore && acc_ignore) {
copter.flightmode_guided.set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
copter.mode_guided.set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f), !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative);
result = MAV_RESULT_ACCEPTED;
} else if (!pos_ignore && vel_ignore && acc_ignore) {
if (copter.flightmode_guided.set_destination(pos_neu_cm, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
if (copter.mode_guided.set_destination(pos_neu_cm, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative)) {
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/avoidance_adsb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle
}

// send target velocity
copter.flightmode_avoid_adsb.set_velocity(velocity_neu);
copter.mode_avoid_adsb.set_velocity(velocity_neu);
return true;
}

Expand All @@ -208,7 +208,7 @@ bool AP_Avoidance_Copter::handle_avoidance_horizontal(const AP_Avoidance::Obstac
velocity_neu.x *= copter.wp_nav->get_speed_xy();
velocity_neu.y *= copter.wp_nav->get_speed_xy();
// send target velocity
copter.flightmode_avoid_adsb.set_velocity(velocity_neu);
copter.mode_avoid_adsb.set_velocity(velocity_neu);
return true;
}

Expand Down Expand Up @@ -240,7 +240,7 @@ bool AP_Avoidance_Copter::handle_avoidance_perpendicular(const AP_Avoidance::Obs
}
}
// send target velocity
copter.flightmode_avoid_adsb.set_velocity(velocity_neu);
copter.mode_avoid_adsb.set_velocity(velocity_neu);
return true;
}

Expand Down
44 changes: 22 additions & 22 deletions ArduCopter/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,7 +292,7 @@ void Copter::exit_mission()
// if we are not on the ground switch to loiter or land
if(!ap.land_complete) {
// try to enter loiter but if that fails land
if(!flightmode_auto.loiter_start()) {
if(!mode_auto.loiter_start()) {
set_mode(LAND, MODE_REASON_MISSION_END);
}
}else{
Expand All @@ -309,7 +309,7 @@ void Copter::exit_mission()
void Copter::do_RTL(void)
{
// start rtl in auto flight mode
flightmode_auto.rtl_start();
mode_auto.rtl_start();
}

/********************************************************************************/
Expand All @@ -320,7 +320,7 @@ void Copter::do_RTL(void)
void Copter::do_takeoff(const AP_Mission::Mission_Command& cmd)
{
// Set wp navigation target to safe altitude above current position
flightmode_auto.takeoff_start(cmd.content.location);
mode_auto.takeoff_start(cmd.content.location);
}

// do_nav_wp - initiate move to next waypoint
Expand Down Expand Up @@ -350,7 +350,7 @@ void Copter::do_nav_wp(const AP_Mission::Mission_Command& cmd)
loiter_time_max = cmd.p1;

// Set wp navigation target
flightmode_auto.wp_start(target_loc);
mode_auto.wp_start(target_loc);

// if no delay set the waypoint as "fast"
if (loiter_time_max == 0 ) {
Expand Down Expand Up @@ -391,13 +391,13 @@ void Copter::do_land(const AP_Mission::Mission_Command& cmd)

Location_Class target_loc = terrain_adjusted_location(cmd);

flightmode_auto.wp_start(target_loc);
mode_auto.wp_start(target_loc);
}else{
// set landing state
land_state = LandStateType_Descending;

// initialise landing controller
flightmode_auto.land_start();
mode_auto.land_start();
}
}

Expand All @@ -411,12 +411,12 @@ void Copter::do_payload_place(const AP_Mission::Mission_Command& cmd)

Location_Class target_loc = terrain_adjusted_location(cmd);

flightmode_auto.wp_start(target_loc);
mode_auto.wp_start(target_loc);
} else {
nav_payload_place.state = PayloadPlaceStateType_Calibrating_Hover_Start;

// initialise placing controller
flightmode_auto.payload_place_start();
mode_auto.payload_place_start();
}
nav_payload_place.descend_max = cmd.p1;
}
Expand Down Expand Up @@ -452,7 +452,7 @@ void Copter::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
}

// start way point navigator and provide it the desired location
flightmode_auto.wp_start(target_loc);
mode_auto.wp_start(target_loc);
}

// do_circle - initiate moving in a circle
Expand Down Expand Up @@ -484,7 +484,7 @@ void Copter::do_circle(const AP_Mission::Mission_Command& cmd)
uint8_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1

// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
flightmode_auto.circle_movetoedge_start(circle_center, circle_radius_m);
mode_auto.circle_movetoedge_start(circle_center, circle_radius_m);
}

// do_loiter_time - initiate loitering at a point for a given time period
Expand Down Expand Up @@ -569,7 +569,7 @@ void Copter::do_spline_wp(const AP_Mission::Mission_Command& cmd)
}

// set spline navigation target
flightmode_auto.spline_start(target_loc, stopped_at_start, seg_end_type, next_loc);
mode_auto.spline_start(target_loc, stopped_at_start, seg_end_type, next_loc);
}

#if NAV_GUIDED == ENABLED
Expand All @@ -578,10 +578,10 @@ void Copter::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 > 0) {
// initialise guided limits
flightmode_guided.limit_init_time_and_pos();
mode_guided.limit_init_time_and_pos();

// set spline navigation target
flightmode_auto.nav_guided_start();
mode_auto.nav_guided_start();
}
}
#endif // NAV_GUIDED
Expand Down Expand Up @@ -649,7 +649,7 @@ void Copter::do_gripper(const AP_Mission::Mission_Command& cmd)
// do_guided_limits - pass guided limits to guided controller
void Copter::do_guided_limits(const AP_Mission::Mission_Command& cmd)
{
flightmode_guided.limit_set(cmd.p1 * 1000, // convert seconds to ms
mode_guided.limit_set(cmd.p1 * 1000, // convert seconds to ms
cmd.content.guided_limits.alt_min * 100.0f, // convert meters to cm
cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm
cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm
Expand Down Expand Up @@ -703,7 +703,7 @@ bool Copter::verify_land()
Vector3f dest = wp_nav->get_wp_destination();

// initialise landing controller
flightmode_auto.land_start(dest);
mode_auto.land_start(dest);

// advance to next state
land_state = LandStateType_Descending;
Expand Down Expand Up @@ -866,7 +866,7 @@ bool Copter::verify_payload_place()
case PayloadPlaceStateType_Ascending_Start: {
Location_Class target_loc = inertial_nav.get_position();
target_loc.alt = nav_payload_place.descend_start_altitude;
flightmode_auto.wp_start(target_loc);
mode_auto.wp_start(target_loc);
nav_payload_place.state = PayloadPlaceStateType_Ascending;
}
FALLTHROUGH;
Expand Down Expand Up @@ -939,7 +939,7 @@ bool Copter::verify_loiter_time()
bool Copter::verify_circle(const AP_Mission::Mission_Command& cmd)
{
// check if we've reached the edge
if (flightmode_auto.mode() == Auto_CircleMoveToEdge) {
if (mode_auto.mode() == Auto_CircleMoveToEdge) {
if (wp_nav->reached_wp_destination()) {
Vector3f curr_pos = inertial_nav.get_position();
Vector3f circle_center = pv_location_to_vector(cmd.content.location);
Expand All @@ -956,7 +956,7 @@ bool Copter::verify_circle(const AP_Mission::Mission_Command& cmd)
}

// start circling
flightmode_auto.circle_start();
mode_auto.circle_start();
}
return false;
}
Expand All @@ -970,7 +970,7 @@ bool Copter::verify_circle(const AP_Mission::Mission_Command& cmd)
// returns true with RTL has completed successfully
bool Copter::verify_RTL()
{
return (flightmode_rtl.state_complete() && (flightmode_rtl.state() == RTL_FinalDescent || flightmode_rtl.state() == RTL_Land));
return (mode_rtl.state_complete() && (mode_rtl.state() == RTL_FinalDescent || mode_rtl.state() == RTL_Land));
}

// verify_spline_wp - check if we have reached the next way point using spline
Expand Down Expand Up @@ -1005,7 +1005,7 @@ bool Copter::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
}

// check time and position limits
return flightmode_guided.limit_check();
return mode_guided.limit_check();
}
#endif // NAV_GUIDED

Expand Down Expand Up @@ -1091,7 +1091,7 @@ bool Copter::verify_yaw()
bool Copter::do_guided(const AP_Mission::Mission_Command& cmd)
{
// only process guided waypoint if we are in guided mode
if (control_mode != GUIDED && !(control_mode == AUTO && flightmode_auto.mode() == Auto_NavGuided)) {
if (control_mode != GUIDED && !(control_mode == AUTO && mode_auto.mode() == Auto_NavGuided)) {
return false;
}

Expand All @@ -1102,7 +1102,7 @@ bool Copter::do_guided(const AP_Mission::Mission_Command& cmd)
{
// set wp_nav's destination
Location_Class dest(cmd.content.location);
return flightmode_guided.set_destination(dest);
return mode_guided.set_destination(dest);
}

case MAV_CMD_CONDITION_YAW:
Expand Down
Loading

0 comments on commit 2d23e1f

Please sign in to comment.