From 1c19d75cf429639ff9ab9ff23ad9fbcd1c936e98 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 5 Dec 2014 09:02:06 +0100 Subject: mc att control: ran fix code style script --- src/modules/mc_att_control/mc_att_control_base.cpp | 36 ++++++++------ src/modules/mc_att_control/mc_att_control_base.h | 3 +- src/modules/mc_att_control/mc_att_control_main.cpp | 23 +++++---- src/modules/mc_att_control/mc_att_control_sim.cpp | 56 ++++++++++++---------- src/modules/mc_att_control/mc_att_control_sim.h | 6 +-- 5 files changed, 71 insertions(+), 53 deletions(-) (limited to 'src') diff --git a/src/modules/mc_att_control/mc_att_control_base.cpp b/src/modules/mc_att_control/mc_att_control_base.cpp index d21deb715..a3b0340d2 100644 --- a/src/modules/mc_att_control/mc_att_control_base.cpp +++ b/src/modules/mc_att_control/mc_att_control_base.cpp @@ -83,10 +83,12 @@ MulticopterAttitudeControlBase::MulticopterAttitudeControlBase() : _I.identity(); } -MulticopterAttitudeControlBase::~MulticopterAttitudeControlBase() { +MulticopterAttitudeControlBase::~MulticopterAttitudeControlBase() +{ } -void MulticopterAttitudeControlBase::control_attitude(float dt) { +void MulticopterAttitudeControlBase::control_attitude(float dt) +{ float yaw_sp_move_rate = 0.0f; _publish_att_sp = false; @@ -94,7 +96,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt) { /* manual input, set or modify attitude setpoint */ if (_v_control_mode.flag_control_velocity_enabled - || _v_control_mode.flag_control_climb_rate_enabled) { + || _v_control_mode.flag_control_climb_rate_enabled) { /* in assisted modes poll 'vehicle_attitude_setpoint' topic and modify it */ vehicle_attitude_setpoint_poll(); } @@ -121,15 +123,17 @@ void MulticopterAttitudeControlBase::control_attitude(float dt) { /* move yaw setpoint */ yaw_sp_move_rate = _manual_control_sp.r * _params.man_yaw_max; _v_att_sp.yaw_body = _wrap_pi( - _v_att_sp.yaw_body + yaw_sp_move_rate * dt); + _v_att_sp.yaw_body + yaw_sp_move_rate * dt); float yaw_offs_max = _params.man_yaw_max / _params.att_p(2); float yaw_offs = _wrap_pi(_v_att_sp.yaw_body - _v_att.yaw); + if (yaw_offs < -yaw_offs_max) { _v_att_sp.yaw_body = _wrap_pi(_v_att.yaw - yaw_offs_max); } else if (yaw_offs > yaw_offs_max) { _v_att_sp.yaw_body = _wrap_pi(_v_att.yaw + yaw_offs_max); } + _v_att_sp.R_valid = false; _publish_att_sp = true; } @@ -146,7 +150,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt) { /* update attitude setpoint if not in position control mode */ _v_att_sp.roll_body = _manual_control_sp.y * _params.man_roll_max; _v_att_sp.pitch_body = -_manual_control_sp.x - * _params.man_pitch_max; + * _params.man_pitch_max; _v_att_sp.R_valid = false; _publish_att_sp = true; } @@ -175,7 +179,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt) { /* copy rotation matrix back to setpoint struct */ memcpy(&_v_att_sp.R_body[0][0], &R_sp.data[0][0], - sizeof(_v_att_sp.R_body)); + sizeof(_v_att_sp.R_body)); _v_att_sp.R_valid = true; } @@ -221,8 +225,8 @@ void MulticopterAttitudeControlBase::control_attitude(float dt) { /* rotation matrix for roll/pitch only rotation */ R_rp = R - * (_I + e_R_cp * e_R_z_sin - + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); + * (_I + e_R_cp * e_R_z_sin + + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); } else { /* zero roll/pitch rotation */ @@ -253,13 +257,14 @@ void MulticopterAttitudeControlBase::control_attitude(float dt) { /* limit yaw rate */ _rates_sp(2) = math::constrain(_rates_sp(2), -_params.yaw_rate_max, - _params.yaw_rate_max); + _params.yaw_rate_max); /* feed forward yaw setpoint rate */ _rates_sp(2) += yaw_sp_move_rate * yaw_w * _params.yaw_ff; } -void MulticopterAttitudeControlBase::control_attitude_rates(float dt) { +void MulticopterAttitudeControlBase::control_attitude_rates(float dt) +{ /* reset integral if disarmed */ if (!_armed.armed) { _rates_int.zero(); @@ -274,7 +279,7 @@ void MulticopterAttitudeControlBase::control_attitude_rates(float dt) { /* angular rates error */ math::Vector < 3 > rates_err = _rates_sp - rates; _att_control = _params.rate_p.emult(rates_err) - + _params.rate_d.emult(_rates_prev - rates) / dt + _rates_int; + + _params.rate_d.emult(_rates_prev - rates) / dt + _rates_int; _rates_prev = rates; /* update integral only if not saturated on low limit */ @@ -282,11 +287,11 @@ void MulticopterAttitudeControlBase::control_attitude_rates(float dt) { for (int i = 0; i < 3; i++) { if (fabsf(_att_control(i)) < _thrust_sp) { float rate_i = _rates_int(i) - + _params.rate_i(i) * rates_err(i) * dt; + + _params.rate_i(i) * rates_err(i) * dt; if (isfinite( - rate_i) && rate_i > -RATES_I_LIMIT && rate_i < RATES_I_LIMIT && - _att_control(i) > -RATES_I_LIMIT && _att_control(i) < RATES_I_LIMIT) { + rate_i) && rate_i > -RATES_I_LIMIT && rate_i < RATES_I_LIMIT && + _att_control(i) > -RATES_I_LIMIT && _att_control(i) < RATES_I_LIMIT) { _rates_int(i) = rate_i; } } @@ -295,7 +300,8 @@ void MulticopterAttitudeControlBase::control_attitude_rates(float dt) { } -void MulticopterAttitudeControlBase::set_actuator_controls() { +void MulticopterAttitudeControlBase::set_actuator_controls() +{ _actuators.control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f; _actuators.control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f; _actuators.control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f; diff --git a/src/modules/mc_att_control/mc_att_control_base.h b/src/modules/mc_att_control/mc_att_control_base.h index 009f76268..e7793e624 100644 --- a/src/modules/mc_att_control/mc_att_control_base.h +++ b/src/modules/mc_att_control/mc_att_control_base.h @@ -64,7 +64,8 @@ #define MIN_TAKEOFF_THRUST 0.2f #define RATES_I_LIMIT 0.3f -class MulticopterAttitudeControlBase { +class MulticopterAttitudeControlBase +{ public: /** * Constructor diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 4709f0487..7a03553f9 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -479,8 +479,9 @@ MulticopterAttitudeControl::task_main() int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit */ - if (pret == 0) + if (pret == 0) { continue; + } /* this is undesirable but not much we can do - might want to flag unhappy status */ if (pret < 0) { @@ -524,10 +525,11 @@ MulticopterAttitudeControl::task_main() if (_att_sp_pub > 0) { orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, - &_v_att_sp); + &_v_att_sp); + } else { _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), - &_v_att_sp); + &_v_att_sp); } } @@ -549,7 +551,8 @@ MulticopterAttitudeControl::task_main() /* attitude controller disabled, poll rates setpoint topic */ if (_v_control_mode.flag_control_manual_enabled) { /* manual rates control - ACRO mode */ - _rates_sp = math::Vector<3>(_manual_control_sp.y, -_manual_control_sp.x, _manual_control_sp.r).emult(_params.acro_rate_max); + _rates_sp = math::Vector<3>(_manual_control_sp.y, -_manual_control_sp.x, + _manual_control_sp.r).emult(_params.acro_rate_max); _thrust_sp = _manual_control_sp.z; /* reset yaw setpoint after ACRO */ @@ -632,18 +635,21 @@ MulticopterAttitudeControl::start() int mc_att_control_main(int argc, char *argv[]) { - if (argc < 1) + if (argc < 1) { errx(1, "usage: mc_att_control {start|stop|status}"); + } if (!strcmp(argv[1], "start")) { - if (mc_att_control::g_control != nullptr) + if (mc_att_control::g_control != nullptr) { errx(1, "already running"); + } mc_att_control::g_control = new MulticopterAttitudeControl; - if (mc_att_control::g_control == nullptr) + if (mc_att_control::g_control == nullptr) { errx(1, "alloc failed"); + } if (OK != mc_att_control::g_control->start()) { delete mc_att_control::g_control; @@ -655,8 +661,9 @@ int mc_att_control_main(int argc, char *argv[]) } if (!strcmp(argv[1], "stop")) { - if (mc_att_control::g_control == nullptr) + if (mc_att_control::g_control == nullptr) { errx(1, "not running"); + } delete mc_att_control::g_control; mc_att_control::g_control = nullptr; diff --git a/src/modules/mc_att_control/mc_att_control_sim.cpp b/src/modules/mc_att_control/mc_att_control_sim.cpp index 61a4237fc..faf729420 100644 --- a/src/modules/mc_att_control/mc_att_control_sim.cpp +++ b/src/modules/mc_att_control/mc_att_control_sim.cpp @@ -46,7 +46,8 @@ using namespace std; #endif -void MulticopterAttitudeControlSim::set_attitude(const Eigen::Quaternion attitude) { +void MulticopterAttitudeControlSim::set_attitude(const Eigen::Quaternion attitude) +{ math::Quaternion quat; quat(0) = (float)attitude.w(); quat(1) = (float)attitude.x(); @@ -58,48 +59,51 @@ void MulticopterAttitudeControlSim::set_attitude(const Eigen::Quaternion _v_att.q[2] = quat(2); _v_att.q[3] = quat(3); - math::Matrix<3,3> Rot = quat.to_dcm(); - _v_att.R[0][0] = Rot(0,0); - _v_att.R[1][0] = Rot(1,0); - _v_att.R[2][0] = Rot(2,0); - _v_att.R[0][1] = Rot(0,1); - _v_att.R[1][1] = Rot(1,1); - _v_att.R[2][1] = Rot(2,1); - _v_att.R[0][2] = Rot(0,2); - _v_att.R[1][2] = Rot(1,2); - _v_att.R[2][2] = Rot(2,2); + math::Matrix<3, 3> Rot = quat.to_dcm(); + _v_att.R[0][0] = Rot(0, 0); + _v_att.R[1][0] = Rot(1, 0); + _v_att.R[2][0] = Rot(2, 0); + _v_att.R[0][1] = Rot(0, 1); + _v_att.R[1][1] = Rot(1, 1); + _v_att.R[2][1] = Rot(2, 1); + _v_att.R[0][2] = Rot(0, 2); + _v_att.R[1][2] = Rot(1, 2); + _v_att.R[2][2] = Rot(2, 2); _v_att.R_valid = true; } -void MulticopterAttitudeControlSim::set_attitude_rates(const Eigen::Vector3d& angular_rate) { +void MulticopterAttitudeControlSim::set_attitude_rates(const Eigen::Vector3d &angular_rate) +{ // check if this is consistent !!! _v_att.rollspeed = angular_rate(0); _v_att.pitchspeed = angular_rate(1); _v_att.yawspeed = angular_rate(2); } -void MulticopterAttitudeControlSim::set_attitude_reference(const Eigen::Vector4d& control_attitude_thrust_reference) { +void MulticopterAttitudeControlSim::set_attitude_reference(const Eigen::Vector4d &control_attitude_thrust_reference) +{ _v_att_sp.roll_body = control_attitude_thrust_reference(0); _v_att_sp.pitch_body = control_attitude_thrust_reference(1); _v_att_sp.yaw_body = control_attitude_thrust_reference(2); - _v_att_sp.thrust = (control_attitude_thrust_reference(3) -30)*(-1)/30; + _v_att_sp.thrust = (control_attitude_thrust_reference(3) - 30) * (-1) / 30; // setup rotation matrix - math::Matrix<3,3> Rot_sp; - Rot_sp.from_euler(_v_att_sp.roll_body,_v_att_sp.pitch_body,_v_att_sp.yaw_body); - _v_att_sp.R_body[0][0] = Rot_sp(0,0); - _v_att_sp.R_body[1][0] = Rot_sp(1,0); - _v_att_sp.R_body[2][0] = Rot_sp(2,0); - _v_att_sp.R_body[0][1] = Rot_sp(0,1); - _v_att_sp.R_body[1][1] = Rot_sp(1,1); - _v_att_sp.R_body[2][1] = Rot_sp(2,1); - _v_att_sp.R_body[0][2] = Rot_sp(0,2); - _v_att_sp.R_body[1][2] = Rot_sp(1,2); - _v_att_sp.R_body[2][2] = Rot_sp(2,2); + math::Matrix<3, 3> Rot_sp; + Rot_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body); + _v_att_sp.R_body[0][0] = Rot_sp(0, 0); + _v_att_sp.R_body[1][0] = Rot_sp(1, 0); + _v_att_sp.R_body[2][0] = Rot_sp(2, 0); + _v_att_sp.R_body[0][1] = Rot_sp(0, 1); + _v_att_sp.R_body[1][1] = Rot_sp(1, 1); + _v_att_sp.R_body[2][1] = Rot_sp(2, 1); + _v_att_sp.R_body[0][2] = Rot_sp(0, 2); + _v_att_sp.R_body[1][2] = Rot_sp(1, 2); + _v_att_sp.R_body[2][2] = Rot_sp(2, 2); } -void MulticopterAttitudeControlSim::get_mixer_input(Eigen::Vector4d& motor_inputs) { +void MulticopterAttitudeControlSim::get_mixer_input(Eigen::Vector4d &motor_inputs) +{ motor_inputs(0) = _actuators.control[0]; motor_inputs(1) = _actuators.control[1]; motor_inputs(2) = _actuators.control[2]; diff --git a/src/modules/mc_att_control/mc_att_control_sim.h b/src/modules/mc_att_control/mc_att_control_sim.h index 20752b054..0b48455af 100644 --- a/src/modules/mc_att_control/mc_att_control_sim.h +++ b/src/modules/mc_att_control/mc_att_control_sim.h @@ -82,9 +82,9 @@ public: /* setters and getters for interface with euroc-gazebo simulator */ void set_attitude(const Eigen::Quaternion attitude); - void set_attitude_rates(const Eigen::Vector3d& angular_rate); - void set_attitude_reference(const Eigen::Vector4d& control_attitude_thrust_reference); - void get_mixer_input(Eigen::Vector4d& motor_inputs); + void set_attitude_rates(const Eigen::Vector3d &angular_rate); + void set_attitude_reference(const Eigen::Vector4d &control_attitude_thrust_reference); + void get_mixer_input(Eigen::Vector4d &motor_inputs); protected: void vehicle_attitude_setpoint_poll() {}; -- cgit v1.2.3