forked from Archive/PX4-Autopilot
Merge pull request #1140 from DonLakeFlyer/UnusedVariableWarnings
Fix unused variable warnings
This commit is contained in:
commit
509180abf6
|
@ -773,7 +773,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
bool updated = false;
|
||||
|
||||
bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
|
||||
rc_calibration_check(mavlink_fd);
|
||||
|
||||
/* Subscribe to safety topic */
|
||||
int safety_sub = orb_subscribe(ORB_ID(safety));
|
||||
|
@ -934,7 +934,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
status_changed = true;
|
||||
|
||||
/* re-check RC calibration */
|
||||
rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
|
||||
rc_calibration_check(mavlink_fd);
|
||||
}
|
||||
|
||||
/* navigation parameters */
|
||||
|
|
|
@ -807,12 +807,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
|||
|
||||
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
|
||||
|
||||
// XXX re-visit
|
||||
float baro_altitude = _global_pos.alt;
|
||||
|
||||
/* filter speed and altitude for controller */
|
||||
math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2);
|
||||
math::Vector<3> accel_earth = _R_nb * accel_body;
|
||||
|
||||
float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt;
|
||||
|
||||
|
@ -945,8 +941,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
|||
float airspeed_land = 1.3f * _parameters.airspeed_min;
|
||||
float airspeed_approach = 1.3f * _parameters.airspeed_min;
|
||||
|
||||
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
|
||||
float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
|
||||
/* Calculate altitude of last ordinary waypoint L */
|
||||
float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
|
||||
|
||||
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
|
||||
|
|
|
@ -220,7 +220,7 @@ int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flight
|
|||
/* Apply overrride given by the limitOverride argument (this is used for limits which are not given by
|
||||
* parameters such as pitch limits with takeoff waypoints or throttle limits when the launchdetector
|
||||
* is running) */
|
||||
bool limitApplied = limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch);
|
||||
limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch);
|
||||
|
||||
/* Write part of the status message */
|
||||
_status.flightPathAngleSp = flightPathAngleSp;
|
||||
|
|
|
@ -346,7 +346,7 @@ MavlinkFTP::_workWrite(Request *req)
|
|||
MavlinkFTP::ErrorCode
|
||||
MavlinkFTP::_workRemove(Request *req)
|
||||
{
|
||||
auto hdr = req->header();
|
||||
//auto hdr = req->header();
|
||||
|
||||
// for now, send error reply
|
||||
return kErrPerm;
|
||||
|
|
|
@ -96,8 +96,11 @@ int test_mathlib(int argc, char *argv[])
|
|||
TEST_OP("Vector<3> %% Vector<3>", v1 % v2);
|
||||
TEST_OP("Vector<3> length", v1.length());
|
||||
TEST_OP("Vector<3> length squared", v1.length_squared());
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
TEST_OP("Vector<3> element read", volatile float a = v1(0));
|
||||
TEST_OP("Vector<3> element read direct", volatile float a = v1.data[0]);
|
||||
#pragma GCC diagnostic pop
|
||||
TEST_OP("Vector<3> element write", v1(0) = 1.0f);
|
||||
TEST_OP("Vector<3> element write direct", v1.data[0] = 1.0f);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue