From f0a20cdc7cdd25cd1beebc12c7d9968f1369a6a3 Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Thu, 22 Oct 2015 11:15:20 -0200 Subject: [PATCH] SITL: remove trailing whitespace --- libraries/SITL/SIM_Aircraft.cpp | 6 +++--- libraries/SITL/SIM_CRRCSim.cpp | 2 +- libraries/SITL/SIM_CRRCSim.h | 2 +- libraries/SITL/SIM_Gazebo.h | 2 +- libraries/SITL/SIM_Gimbal.cpp | 20 ++++++++++---------- libraries/SITL/SIM_Gimbal.h | 2 +- libraries/SITL/SIM_Helicopter.cpp | 8 ++++---- libraries/SITL/SIM_JSBSim.cpp | 20 ++++++++++---------- libraries/SITL/SIM_JSBSim.h | 14 +++++++------- libraries/SITL/SIM_Tracker.cpp | 8 ++++---- libraries/SITL/SIM_last_letter.h | 2 +- libraries/SITL/SITL.cpp | 6 +++--- 12 files changed, 46 insertions(+), 46 deletions(-) diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 1f684862c9..d7f1aa88d5 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -152,9 +152,9 @@ void Aircraft::adjust_frame_time(float new_rate) } } -/* +/* try to synchronise simulation time with wall clock time, taking - into account desired speedup + into account desired speedup This tries to take account of possible granularity of get_wall_time_us() so it works reasonably well on windows */ @@ -173,7 +173,7 @@ void Aircraft::sync_frame_time(void) } #if 0 ::printf("achieved_rate_hz=%.3f rate=%.2f rate_hz=%.3f sft=%.1f\n", - (double)achieved_rate_hz, + (double)achieved_rate_hz, (double)rate, (double)rate_hz, (double)scaled_frame_time_us); diff --git a/libraries/SITL/SIM_CRRCSim.cpp b/libraries/SITL/SIM_CRRCSim.cpp index e0b73dd5b6..a72494a0ea 100644 --- a/libraries/SITL/SIM_CRRCSim.cpp +++ b/libraries/SITL/SIM_CRRCSim.cpp @@ -59,7 +59,7 @@ void CRRCSim::send_servos_heli(const struct sitl_input &input) float roll_rate = (swash1 - swash2)/2; float pitch_rate = -((swash1 + swash2)/2.0 - swash3)/2; float yaw_rate = -(tail_rotor - 0.5); - + servo_packet pkt; pkt.roll_rate = constrain_float(roll_rate, -0.5, 0.5); pkt.pitch_rate = constrain_float(pitch_rate, -0.5, 0.5); diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index be0caa2797..18adb43638 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -52,7 +52,7 @@ private: float yaw_rate; float col_pitch; }; - + /* reply packet sent from CRRCSim to ArduPilot */ diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index 120cff8ea5..49ff109533 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -48,7 +48,7 @@ private: struct servo_packet { float motor_speed[4]; }; - + /* reply packet sent from Gazebo to ArduPilot */ diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index 181e6ed2e2..13e9a7f121 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -57,8 +57,8 @@ void Gimbal::update(void) Matrix3f vehicle_dcm; vehicle_dcm.from_euler(radians(fdm.rollDeg), radians(fdm.pitchDeg), radians(fdm.yawDeg)); - Vector3f vehicle_gyro = Vector3f(radians(fdm.rollRate), - radians(fdm.pitchRate), + Vector3f vehicle_gyro = Vector3f(radians(fdm.rollRate), + radians(fdm.pitchRate), radians(fdm.yawRate)); Vector3f vehicle_accel_body = Vector3f(fdm.xAccel, fdm.yAccel, fdm.zAccel); @@ -79,7 +79,7 @@ void Gimbal::update(void) Matrix3f rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm; joint_angles = rotmat_copter_gimbal.transposed().to_euler312(); - + /* 4) For each of the three joints, calculate upper and lower rate limits from the corresponding angle limits and current joint angles @@ -145,7 +145,7 @@ void Gimbal::update(void) // in an inertial frame of reference // demandedGimbalRatesInertial(X,Y,Z) = relativeGimbalRate(X,Y,Z) + copterAngRate_G // Vector3f demandedGimbalRatesInertial = relativeGimbalRate + copterAngRate_G; - + // for the moment we will set gyros equal to demanded_angular_rate gimbal_angular_rate = demRateRaw; // demandedGimbalRatesInertial + true_gyro_bias - supplied_gyro_bias @@ -198,7 +198,7 @@ void Gimbal::send_report(void) mavlink_message_t msg; mavlink_status_t status; if (mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status, - buf[i], + buf[i], &msg, &status) == MAVLINK_FRAMING_OK) { switch (msg.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: { @@ -249,8 +249,8 @@ void Gimbal::send_report(void) mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); uint8_t saved_seq = chan0_status->current_tx_seq; chan0_status->current_tx_seq = mavlink.seq; - len = mavlink_msg_heartbeat_encode(vehicle_system_id, - vehicle_component_id, + len = mavlink_msg_heartbeat_encode(vehicle_system_id, + vehicle_component_id, &msg, &heartbeat); chan0_status->current_tx_seq = saved_seq; @@ -282,13 +282,13 @@ void Gimbal::send_report(void) mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); uint8_t saved_seq = chan0_status->current_tx_seq; chan0_status->current_tx_seq = mavlink.seq; - len = mavlink_msg_gimbal_report_encode(vehicle_system_id, - vehicle_component_id, + len = mavlink_msg_gimbal_report_encode(vehicle_system_id, + vehicle_component_id, &msg, &gimbal_report); chan0_status->current_tx_seq = saved_seq; mav_socket.send(&msg.magic, len); - + delta_velocity.zero(); delta_angle.zero(); } diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index 9748c7ed52..162d7a58c6 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -71,7 +71,7 @@ private: // reporting period in ms const float reporting_period_ms; - + // integral of gyro vector over last time interval. In radians Vector3f delta_angle; diff --git a/libraries/SITL/SIM_Helicopter.cpp b/libraries/SITL/SIM_Helicopter.cpp index e8329c54a5..151667b222 100644 --- a/libraries/SITL/SIM_Helicopter.cpp +++ b/libraries/SITL/SIM_Helicopter.cpp @@ -87,14 +87,14 @@ void Helicopter::update(const struct sitl_input &input) // simulate a traditional helicopter float tail_rotor = (input.servos[3]-1000) / 1000.0f; - + thrust = (rsc/rsc_setpoint) * (swash1+swash2+swash3) / 3.0f; torque_effect_accel = (rsc_scale+thrust) * rotor_rot_accel; roll_rate = swash1 - swash2; pitch_rate = (swash1+swash2) / 2.0f - swash3; yaw_rate = tail_rotor - 0.5f; - + lateral_y_thrust = yaw_rate * rsc_scale * tail_thrust_scale; break; } @@ -105,7 +105,7 @@ void Helicopter::update(const struct sitl_input &input) float swash4 = (input.servos[3]-1000) / 1000.0f; float swash5 = (input.servos[4]-1000) / 1000.0f; float swash6 = (input.servos[5]-1000) / 1000.0f; - + thrust = (rsc / rsc_setpoint) * (swash1+swash2+swash3+swash4+swash5+swash6) / 6.0f; torque_effect_accel = (rsc_scale + rsc / rsc_setpoint) * rotor_rot_accel * ((swash1+swash2+swash3) - (swash4+swash5+swash6)); @@ -120,7 +120,7 @@ void Helicopter::update(const struct sitl_input &input) float right_rotor = (input.servos[3]-1000) / 1000.0f; float left_rotor = (input.servos[4]-1000) / 1000.0f; - + thrust = (rsc/rsc_setpoint) * (swash1+swash2+swash3) / 3.0f; torque_effect_accel = (rsc_scale+thrust) * rotor_rot_accel; diff --git a/libraries/SITL/SIM_JSBSim.cpp b/libraries/SITL/SIM_JSBSim.cpp index d4d4a48c84..2f1b22547e 100644 --- a/libraries/SITL/SIM_JSBSim.cpp +++ b/libraries/SITL/SIM_JSBSim.cpp @@ -122,7 +122,7 @@ bool JSBSim::create_templates(void) if (f == NULL) { hal.scheduler->panic("Unable to create jsbsim fgout script"); } - fprintf(f, "\n" + fprintf(f, "\n" "\n", fdm_port); fclose(f); @@ -135,7 +135,7 @@ bool JSBSim::create_templates(void) } float r, p, y; dcm.to_euler(&r, &p, &y); - fprintf(f, + fprintf(f, "\n" "\n" " %f \n" @@ -172,7 +172,7 @@ bool JSBSim::start_JSBSim(void) int p[2]; int devnull = open("/dev/null", O_RDWR); if (pipe(p) != 0) { - hal.scheduler->panic("Unable to create pipe"); + hal.scheduler->panic("Unable to create pipe"); } pid_t child_pid = fork(); if (child_pid == 0) { @@ -194,8 +194,8 @@ bool JSBSim::start_JSBSim(void) exit(1); } - int ret = execlp("JSBSim", - "JSBSim", + int ret = execlp("JSBSim", + "JSBSim", "--realtime", "--suspend", "--nice", @@ -218,7 +218,7 @@ bool JSBSim::start_JSBSim(void) } if (!expect("JSBSim Execution beginning")) { - hal.scheduler->panic("Failed to start JSBSim"); + hal.scheduler->panic("Failed to start JSBSim"); } if (!open_control_socket()) { hal.scheduler->panic("Failed to open JSBSim control socket"); @@ -252,7 +252,7 @@ bool JSBSim::expect(const char *str) { const char *basestr = str; while (*str) { - char c; + char c; if (read(jsbsim_stdout, &c, 1) != 1) { return false; } @@ -283,7 +283,7 @@ bool JSBSim::open_control_socket(void) sock_control.set_blocking(false); opened_control_socket = true; - char startup[] = + char startup[] = "info\n" "resume\n" "step\n" @@ -337,7 +337,7 @@ void JSBSim::send_servos(const struct sitl_input &input) rudder = (ch2+ch1)/2.0f; } float wind_speed_fps = input.wind.speed / FEET_TO_METERS; - asprintf(&buf, + asprintf(&buf, "set fcs/aileron-cmd-norm %f\n" "set fcs/elevator-cmd-norm %f\n" "set fcs/rudder-cmd-norm %f\n" @@ -370,7 +370,7 @@ void JSBSim::send_servos(const struct sitl_input &input) /* nasty hack .... JSBSim sends in little-endian */ -void FGNetFDM::ByteSwap(void) +void FGNetFDM::ByteSwap(void) { uint32_t *buf = (uint32_t *)this; for (uint16_t i=0; i