Skip to content
Snippets Groups Projects
Commit 53e6d7eb authored by Daniel Agar's avatar Daniel Agar
Browse files

delete examples mc_att_control_multiplatform

parent b8e24b5d
No related branches found
No related tags found
No related merge requests found
Showing
with 0 additions and 1458 deletions
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE examples__mc_att_control_multiplatform
MAIN mc_att_control_m
SRCS
mc_att_control_main.cpp
mc_att_control_start_nuttx.cpp
mc_att_control.cpp
mc_att_control_base.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control.cpp
* Multicopter attitude controller.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Roman Bapst <bapstr@ethz.ch>
*/
#include "mc_att_control.h"
#include "mc_att_control_params.h"
#include "math.h"
#define YAW_DEADZONE 0.05f
#define MIN_TAKEOFF_THRUST 0.2f
#define RATES_I_LIMIT 0.3f
MulticopterAttitudeControlMultiplatform::MulticopterAttitudeControlMultiplatform() :
MulticopterAttitudeControlBase(),
_actuators_0_circuit_breaker_enabled(false),
/* publications */
_v_rates_sp_pub(nullptr),
_actuators_0_pub(nullptr),
_n(_appState),
/* parameters */
_params_handles(
{
.roll_p = px4::ParameterFloat("MP_ROLL_P", PARAM_MP_ROLL_P_DEFAULT),
.roll_rate_p = px4::ParameterFloat("MP_ROLLRATE_P", PARAM_MP_ROLLRATE_P_DEFAULT),
.roll_rate_i = px4::ParameterFloat("MP_ROLLRATE_I", PARAM_MP_ROLLRATE_I_DEFAULT),
.roll_rate_d = px4::ParameterFloat("MP_ROLLRATE_D", PARAM_MP_ROLLRATE_D_DEFAULT),
.pitch_p = px4::ParameterFloat("MP_PITCH_P", PARAM_MP_PITCH_P_DEFAULT),
.pitch_rate_p = px4::ParameterFloat("MP_PITCHRATE_P", PARAM_MP_PITCHRATE_P_DEFAULT),
.pitch_rate_i = px4::ParameterFloat("MP_PITCHRATE_I", PARAM_MP_PITCHRATE_I_DEFAULT),
.pitch_rate_d = px4::ParameterFloat("MP_PITCHRATE_D", PARAM_MP_PITCHRATE_D_DEFAULT),
.yaw_p = px4::ParameterFloat("MP_YAW_P", PARAM_MP_YAW_P_DEFAULT),
.yaw_rate_p = px4::ParameterFloat("MP_YAWRATE_P", PARAM_MP_YAWRATE_P_DEFAULT),
.yaw_rate_i = px4::ParameterFloat("MP_YAWRATE_I", PARAM_MP_YAWRATE_I_DEFAULT),
.yaw_rate_d = px4::ParameterFloat("MP_YAWRATE_D", PARAM_MP_YAWRATE_D_DEFAULT),
.yaw_ff = px4::ParameterFloat("MP_YAW_FF", PARAM_MP_YAW_FF_DEFAULT),
.yaw_rate_max = px4::ParameterFloat("MP_YAWRATE_MAX", PARAM_MP_YAWRATE_MAX_DEFAULT),
.acro_roll_max = px4::ParameterFloat("MP_ACRO_R_MAX", PARAM_MP_ACRO_R_MAX_DEFAULT),
.acro_pitch_max = px4::ParameterFloat("MP_ACRO_P_MAX", PARAM_MP_ACRO_P_MAX_DEFAULT),
.acro_yaw_max = px4::ParameterFloat("MP_ACRO_Y_MAX", PARAM_MP_ACRO_Y_MAX_DEFAULT)
}),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "mc_att_control"))
{
/* fetch initial parameter values */
parameters_update();
/*
* do subscriptions
*/
_v_att = _n.subscribe<px4_vehicle_attitude>(&MulticopterAttitudeControlMultiplatform::handle_vehicle_attitude, this, 0);
_v_att_sp = _n.subscribe<px4_vehicle_attitude_setpoint>(0);
_v_rates_sp = _n.subscribe<px4_vehicle_rates_setpoint>(0);
_v_control_mode = _n.subscribe<px4_vehicle_control_mode>(0);
_parameter_update = _n.subscribe<px4_parameter_update>(
&MulticopterAttitudeControlMultiplatform::handle_parameter_update, this, 1000);
_manual_control_sp = _n.subscribe<px4_manual_control_setpoint>(0);
_armed = _n.subscribe<px4_actuator_armed>(0);
_v_status = _n.subscribe<px4_vehicle_status>(0);
}
MulticopterAttitudeControlMultiplatform::~MulticopterAttitudeControlMultiplatform()
{
}
int
MulticopterAttitudeControlMultiplatform::parameters_update()
{
/* roll gains */
_params.att_p(0) = _params_handles.roll_p.update();
_params.rate_p(0) = _params_handles.roll_rate_p.update();
_params.rate_i(0) = _params_handles.roll_rate_i.update();
_params.rate_d(0) = _params_handles.roll_rate_d.update();
/* pitch gains */
_params.att_p(1) = _params_handles.pitch_p.update();
_params.rate_p(1) = _params_handles.pitch_rate_p.update();
_params.rate_i(1) = _params_handles.pitch_rate_i.update();
_params.rate_d(1) = _params_handles.pitch_rate_d.update();
/* yaw gains */
_params.att_p(2) = _params_handles.yaw_p.update();
_params.rate_p(2) = _params_handles.yaw_rate_p.update();
_params.rate_i(2) = _params_handles.yaw_rate_i.update();
_params.rate_d(2) = _params_handles.yaw_rate_d.update();
_params.yaw_ff = _params_handles.yaw_ff.update();
_params.yaw_rate_max = math::radians(_params_handles.yaw_rate_max.update());
/* acro control scale */
_params.acro_rate_max(0) = math::radians(_params_handles.acro_roll_max.update());
_params.acro_rate_max(1) = math::radians(_params_handles.acro_pitch_max.update());
_params.acro_rate_max(2) = math::radians(_params_handles.acro_yaw_max.update());
_actuators_0_circuit_breaker_enabled = circuit_breaker_enabled("CBRK_RATE_CTRL", CBRK_RATE_CTRL_KEY);
return OK;
}
void MulticopterAttitudeControlMultiplatform::handle_parameter_update(const px4_parameter_update &msg)
{
parameters_update();
}
void MulticopterAttitudeControlMultiplatform::handle_vehicle_attitude(const px4_vehicle_attitude &msg)
{
perf_begin(_loop_perf);
/* run controller on attitude changes */
static uint64_t last_run = 0;
float dt = (px4::get_time_micros() - last_run) / 1000000.0f;
last_run = px4::get_time_micros();
/* guard against too small (< 2ms) and too large (> 20ms) dt's */
if (dt < 0.002f) {
dt = 0.002f;
} else if (dt > 0.02f) {
dt = 0.02f;
}
if (_v_control_mode->data().flag_control_attitude_enabled) {
control_attitude(dt);
/* publish attitude rates setpoint */
_v_rates_sp_mod.data().roll = _rates_sp(0);
_v_rates_sp_mod.data().pitch = _rates_sp(1);
_v_rates_sp_mod.data().yaw = _rates_sp(2);
_v_rates_sp_mod.data().thrust = _thrust_sp;
_v_rates_sp_mod.data().timestamp = px4::get_time_micros();
if (_v_rates_sp_pub != nullptr) {
_v_rates_sp_pub->publish(_v_rates_sp_mod);
} else {
if (_v_status->data().is_vtol) {
//XXX add a second publisher?
// _v_rates_sp_pub = _n.advertise<px4_mc_virtual_rates_setpoint>();
} else {
_v_rates_sp_pub = _n.advertise<px4_vehicle_rates_setpoint>();
}
}
} else {
/* attitude controller disabled, poll rates setpoint topic */
if (_v_control_mode->data().flag_control_manual_enabled) {
/* manual rates control - ACRO mode */
_rates_sp = math::Vector<3>(_manual_control_sp->data().y, -_manual_control_sp->data().x,
_manual_control_sp->data().r).emult(_params.acro_rate_max);
_thrust_sp = _manual_control_sp->data().z;
/* publish attitude rates setpoint */
_v_rates_sp_mod.data().roll = _rates_sp(0);
_v_rates_sp_mod.data().pitch = _rates_sp(1);
_v_rates_sp_mod.data().yaw = _rates_sp(2);
_v_rates_sp_mod.data().thrust = _thrust_sp;
_v_rates_sp_mod.data().timestamp = px4::get_time_micros();
if (_v_rates_sp_pub != nullptr) {
_v_rates_sp_pub->publish(_v_rates_sp_mod);
} else {
if (_v_status->data().is_vtol) {
//XXX add a second publisher?
// _v_rates_sp_pub = _n.advertise<px4_mc_virtual_rates_setpoint>();
} else {
_v_rates_sp_pub = _n.advertise<px4_vehicle_rates_setpoint>();
}
}
} else {
/* attitude controller disabled, poll rates setpoint topic */
_rates_sp(0) = _v_rates_sp->data().roll;
_rates_sp(1) = _v_rates_sp->data().pitch;
_rates_sp(2) = _v_rates_sp->data().yaw;
_thrust_sp = _v_rates_sp->data().thrust;
}
}
if (_v_control_mode->data().flag_control_rates_enabled) {
control_attitude_rates(dt);
/* publish actuator controls */
_actuators.data().control[0] = (PX4_ISFINITE(_att_control(0))) ? _att_control(0) : 0.0f;
_actuators.data().control[1] = (PX4_ISFINITE(_att_control(1))) ? _att_control(1) : 0.0f;
_actuators.data().control[2] = (PX4_ISFINITE(_att_control(2))) ? _att_control(2) : 0.0f;
_actuators.data().control[3] = (PX4_ISFINITE(_thrust_sp)) ? _thrust_sp : 0.0f;
_actuators.data().timestamp = px4::get_time_micros();
if (!_actuators_0_circuit_breaker_enabled) {
if (_actuators_0_pub != nullptr) {
_actuators_0_pub->publish(_actuators);
} else {
if (_v_status->data().is_vtol) {
//XXX add a second publisher?
// _actuators_0_pub = _n.advertise<px4_actuator_controls_virtual_mc>();
} else {
_actuators_0_pub = _n.advertise<px4_actuator_controls_0>();
}
}
}
}
}
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control.h
* Multicopter attitude controller.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Roman Bapst <bapstr@ethz.ch>
*
* The controller has two loops: P loop for angular error and PD loop for angular rate error.
* Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch.
* For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw,
* so actual rotation axis is not constant. For large deviations controller rotates copter around fixed axis.
* These two approaches fused seamlessly with weight depending on angular error.
* When thrust vector directed near-horizontally (e.g. roll ~= PI/2) yaw setpoint ignored because of singularity.
* Controller doesn't use Euler angles for work, they generated only for more human-friendly control and logging.
* If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers.
*/
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <math.h>
#include <poll.h>
#include <systemlib/perf_counter.h>
#include <systemlib/circuit_breaker.h>
#include <lib/mathlib/mathlib.h>
#include "mc_att_control_base.h"
class MulticopterAttitudeControlMultiplatform :
public MulticopterAttitudeControlBase
{
public:
/**
* Constructor
*/
MulticopterAttitudeControlMultiplatform();
/**
* Destructor, also kills the sensors task.
*/
~MulticopterAttitudeControlMultiplatform();
/* Callbacks for topics */
void handle_vehicle_attitude(const px4_vehicle_attitude &msg);
void handle_parameter_update(const px4_parameter_update &msg);
void spin() { _n.spin(); }
private:
bool _actuators_0_circuit_breaker_enabled; /**< circuit breaker to suppress output */
px4::Publisher<px4_vehicle_rates_setpoint> *_v_rates_sp_pub; /**< rate setpoint publication */
px4::Publisher<px4_actuator_controls_0> *_actuators_0_pub; /**< attitude actuator controls publication */
px4::NodeHandle _n;
px4::AppState _appState;
struct {
px4::ParameterFloat roll_p;
px4::ParameterFloat roll_rate_p;
px4::ParameterFloat roll_rate_i;
px4::ParameterFloat roll_rate_d;
px4::ParameterFloat pitch_p;
px4::ParameterFloat pitch_rate_p;
px4::ParameterFloat pitch_rate_i;
px4::ParameterFloat pitch_rate_d;
px4::ParameterFloat yaw_p;
px4::ParameterFloat yaw_rate_p;
px4::ParameterFloat yaw_rate_i;
px4::ParameterFloat yaw_rate_d;
px4::ParameterFloat yaw_ff;
px4::ParameterFloat yaw_rate_max;
px4::ParameterFloat acro_roll_max;
px4::ParameterFloat acro_pitch_max;
px4::ParameterFloat acro_yaw_max;
} _params_handles; /**< handles for interesting parameters */
perf_counter_t _loop_perf; /**< loop performance counter */
/**
* Update our local parameter cache.
*/
int parameters_update();
};
/* Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_base.cpp
*
* MC Attitude Controller : Control and math code
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Roman Bapst <bapstr@ethz.ch>
*
*/
#include "mc_att_control_base.h"
#include <geo/geo.h>
#include <math.h>
#include <lib/mathlib/mathlib.h>
#ifdef CONFIG_ARCH_ARM
#else
#include <cmath>
using namespace std;
#endif
MulticopterAttitudeControlBase::MulticopterAttitudeControlBase() :
_v_rates_sp_mod(),
_actuators(),
_publish_att_sp(false)
{
_params.att_p.zero();
_params.rate_p.zero();
_params.rate_i.zero();
_params.rate_d.zero();
_params.yaw_ff = 0.0f;
_params.yaw_rate_max = 0.0f;
_params.acro_rate_max.zero();
_rates_prev.zero();
_rates_sp.zero();
_rates_int.zero();
_thrust_sp = 0.0f;
_att_control.zero();
_I.identity();
}
MulticopterAttitudeControlBase::~MulticopterAttitudeControlBase()
{
}
void MulticopterAttitudeControlBase::control_attitude(float dt)
{
_thrust_sp = _v_att_sp->data().thrust;
/* construct attitude setpoint rotation matrix */
math::Quaternion q_sp(&_v_att_sp->data().q_d[0]);
math::Matrix<3, 3> R_sp = q_sp.to_dcm();
/* rotation matrix for current state */
math::Quaternion q(&_v_att->data().q[0]);
math::Matrix<3, 3> R = q.to_dcm();
/* all input data is ready, run controller itself */
/* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */
math::Vector <3> R_z(R(0, 2), R(1, 2), R(2, 2));
math::Vector <3> R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2));
/* axis and sin(angle) of desired rotation */
math::Vector <3> e_R = R.transposed() * (R_z % R_sp_z);
/* calculate angle error */
float e_R_z_sin = e_R.length();
float e_R_z_cos = R_z * R_sp_z;
/* calculate weight for yaw control */
float yaw_w = R_sp(2, 2) * R_sp(2, 2);
/* calculate rotation matrix after roll/pitch only rotation */
math::Matrix<3, 3> R_rp;
if (e_R_z_sin > 0.0f) {
/* get axis-angle representation */
float e_R_z_angle = atan2f(e_R_z_sin, e_R_z_cos);
math::Vector <3> e_R_z_axis = e_R / e_R_z_sin;
e_R = e_R_z_axis * e_R_z_angle;
/* cross product matrix for e_R_axis */
math::Matrix<3, 3> e_R_cp;
e_R_cp.zero();
e_R_cp(0, 1) = -e_R_z_axis(2);
e_R_cp(0, 2) = e_R_z_axis(1);
e_R_cp(1, 0) = e_R_z_axis(2);
e_R_cp(1, 2) = -e_R_z_axis(0);
e_R_cp(2, 0) = -e_R_z_axis(1);
e_R_cp(2, 1) = e_R_z_axis(0);
/* 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));
} else {
/* zero roll/pitch rotation */
R_rp = R;
}
/* R_rp and R_sp has the same Z axis, calculate yaw error */
math::Vector <3> R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0));
math::Vector <3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0));
e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w;
if (e_R_z_cos < 0.0f) {
/* for large thrust vector rotations use another rotation method:
* calculate angle and axis for R -> R_sp rotation directly */
math::Quaternion ql;
ql.from_dcm(R.transposed() * R_sp);
math::Vector <3> e_R_d = ql.imag();
e_R_d.normalize();
e_R_d *= 2.0f * atan2f(e_R_d.length(), ql(0));
/* use fusion of Z axis based rotation and direct rotation */
float direct_w = e_R_z_cos * e_R_z_cos * yaw_w;
e_R = e_R * (1.0f - direct_w) + e_R_d * direct_w;
}
/* calculate angular rates setpoint */
_rates_sp = _params.att_p.emult(e_R);
/* limit yaw rate */
_rates_sp(2) = math::constrain(_rates_sp(2), -_params.yaw_rate_max,
_params.yaw_rate_max);
/* feed forward yaw setpoint rate */
_rates_sp(2) += _v_att_sp->data().yaw_sp_move_rate * yaw_w * _params.yaw_ff;
}
void MulticopterAttitudeControlBase::control_attitude_rates(float dt)
{
/* reset integral if disarmed */
if (!_armed->data().armed || !_v_status->data().is_rotary_wing) {
_rates_int.zero();
}
/* current body angular rates */
math::Vector < 3 > rates;
rates(0) = _v_att->data().rollspeed;
rates(1) = _v_att->data().pitchspeed;
rates(2) = _v_att->data().yawspeed;
/* 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;
_rates_prev = rates;
/* update integral only if not saturated on low limit */
if (_thrust_sp > MIN_TAKEOFF_THRUST) {
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;
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) {
_rates_int(i) = rate_i;
}
}
}
}
}
void MulticopterAttitudeControlBase::set_actuator_controls()
{
_actuators.data().control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f;
_actuators.data().control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f;
_actuators.data().control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f;
_actuators.data().control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f;
}
#ifndef MC_ATT_CONTROL_BASE_H_
#define MC_ATT_CONTROL_BASE_H_
/* Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_base.h
*
* MC Attitude Controller : Control and math code
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Roman Bapst <bapstr@ethz.ch>
*
*/
#include <px4.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <math.h>
#include <systemlib/perf_counter.h>
#include <lib/mathlib/mathlib.h>
#define YAW_DEADZONE 0.05f
#define MIN_TAKEOFF_THRUST 0.2f
#define RATES_I_LIMIT 0.3f
using namespace px4;
class MulticopterAttitudeControlBase
{
public:
/**
* Constructor
*/
MulticopterAttitudeControlBase();
/**
* Destructor
*/
~MulticopterAttitudeControlBase();
/**
* Start the sensors task.
*
* @return OK on success.
*/
void control_attitude(float dt);
void control_attitude_rates(float dt);
void set_actuator_controls();
protected:
px4::Subscriber<px4_vehicle_attitude> *_v_att; /**< vehicle attitude */
px4::Subscriber<px4_vehicle_attitude_setpoint> *_v_att_sp; /**< vehicle attitude setpoint */
px4::Subscriber<px4_vehicle_rates_setpoint> *_v_rates_sp; /**< vehicle rates setpoint */
px4::Subscriber<px4_vehicle_control_mode> *_v_control_mode; /**< vehicle control mode */
px4::Subscriber<px4_parameter_update> *_parameter_update; /**< parameter update */
px4::Subscriber<px4_manual_control_setpoint> *_manual_control_sp; /**< manual control setpoint */
px4::Subscriber<px4_actuator_armed> *_armed; /**< actuator arming status */
px4::Subscriber<px4_vehicle_status> *_v_status; /**< vehicle status */
px4_vehicle_rates_setpoint _v_rates_sp_mod; /**< vehicle rates setpoint
that gets published eventually*/
px4_actuator_controls_0 _actuators; /**< actuator controls */
math::Vector<3> _rates_prev; /**< angular rates on previous step */
math::Vector<3> _rates_sp; /**< angular rates setpoint */
math::Vector<3> _rates_int; /**< angular rates integral error */
float _thrust_sp; /**< thrust setpoint */
math::Vector<3> _att_control; /**< attitude control vector */
math::Matrix<3, 3> _I; /**< identity matrix */
bool _reset_yaw_sp; /**< reset yaw setpoint flag */
struct {
math::Vector<3> att_p; /**< P gain for angular error */
math::Vector<3> rate_p; /**< P gain for angular rate error */
math::Vector<3> rate_i; /**< I gain for angular rate error */
math::Vector<3> rate_d; /**< D gain for angular rate error */
float yaw_ff; /**< yaw control feed-forward */
float yaw_rate_max; /**< max yaw rate */
math::Vector<3> acro_rate_max; /**< max attitude rates in acro mode */
int32_t autostart_id;
} _params;
bool _publish_att_sp;
};
#endif /* MC_ATT_CONTROL_BASE_H_ */
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_main.cpp
* Multicopter attitude controller.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Roman Bapst <bapstr@ethz.ch>
*
* The controller has two loops: P loop for angular error and PD loop for angular rate error.
* Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch.
* For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw,
* so actual rotation axis is not constant. For large deviations controller rotates copter around fixed axis.
* These two approaches fused seamlessly with weight depending on angular error.
* When thrust vector directed near-horizontally (e.g. roll ~= PI/2) yaw setpoint ignored because of singularity.
* Controller doesn't use Euler angles for work, they generated only for more human-friendly control and logging.
* If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers.
*/
#include "mc_att_control.h"
bool mc_att_control_thread_running = false; /**< Deamon status flag */
#if defined(__PX4_ROS)
int main(int argc, char **argv)
#else
int mc_att_control_start_main(int argc, char **argv); // Prototype for missing declearation error with nuttx
int mc_att_control_start_main(int argc, char **argv)
#endif
{
px4::init(argc, argv, "mc_att_control_m");
PX4_INFO("starting");
MulticopterAttitudeControlMultiplatform attctl;
mc_att_control_thread_running = true;
attctl.spin();
PX4_INFO("exiting.");
mc_att_control_thread_running = false;
return 0;
}
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_params.c
* Parameters for multicopter attitude controller.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lorenz@px4.io>
* @author Anton Babushkin <anton.babushkin@me.com>
*/
/**
* Roll P gain
*
* Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ROLL_P);
/**
* Roll rate P gain
*
* Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ROLLRATE_P);
/**
* Roll rate I gain
*
* Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ROLLRATE_I);
/**
* Roll rate D gain
*
* Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ROLLRATE_D);
/**
* Pitch P gain
*
* Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
*
* @unit 1/s
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_PITCH_P);
/**
* Pitch rate P gain
*
* Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_PITCHRATE_P);
/**
* Pitch rate I gain
*
* Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_PITCHRATE_I);
/**
* Pitch rate D gain
*
* Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_PITCHRATE_D);
/**
* Yaw P gain
*
* Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
*
* @unit 1/s
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_YAW_P);
/**
* Yaw rate P gain
*
* Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_YAWRATE_P);
/**
* Yaw rate I gain
*
* Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_YAWRATE_I);
/**
* Yaw rate D gain
*
* Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
*
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_YAWRATE_D);
/**
* Yaw feed forward
*
* Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_YAW_FF);
/**
* Max yaw rate
*
* Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.
*
* @unit deg/s
* @min 0.0
* @max 360.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_YAWRATE_MAX);
/**
* Max acro roll rate
*
* @unit deg/s
* @min 0.0
* @max 360.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ACRO_R_MAX);
/**
* Max acro pitch rate
*
* @unit deg/s
* @min 0.0
* @max 360.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ACRO_P_MAX);
/**
* Max acro yaw rate
*
* @unit deg/s
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MP_ACRO_Y_MAX);
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file MP_att_control_params.h
* Parameters for multicopter attitude controller.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#define PARAM_MP_ROLL_P_DEFAULT 6.0f
#define PARAM_MP_ROLLRATE_P_DEFAULT 0.1f
#define PARAM_MP_ROLLRATE_I_DEFAULT 0.0f
#define PARAM_MP_ROLLRATE_D_DEFAULT 0.002f
#define PARAM_MP_PITCH_P_DEFAULT 6.0f
#define PARAM_MP_PITCHRATE_P_DEFAULT 0.1f
#define PARAM_MP_PITCHRATE_I_DEFAULT 0.0f
#define PARAM_MP_PITCHRATE_D_DEFAULT 0.002f
#define PARAM_MP_YAW_P_DEFAULT 2.0f
#define PARAM_MP_YAWRATE_P_DEFAULT 0.3f
#define PARAM_MP_YAWRATE_I_DEFAULT 0.0f
#define PARAM_MP_YAWRATE_D_DEFAULT 0.0f
#define PARAM_MP_YAW_FF_DEFAULT 0.5f
#define PARAM_MP_YAWRATE_MAX_DEFAULT 60.0f
#define PARAM_MP_ACRO_R_MAX_DEFAULT 35.0f
#define PARAM_MP_ACRO_P_MAX_DEFAULT 35.0f
#define PARAM_MP_ACRO_Y_MAX_DEFAULT 120.0f
/* Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_sim.cpp
*
* MC Attitude Controller Interface for usage in a simulator
*
* @author Roman Bapst <bapstr@ethz.ch>
*
*/
#include "mc_att_control_sim.h"
#include <geo/geo.h>
#include <math.h>
#ifdef CONFIG_ARCH_ARM
#else
#include <cmath>
using namespace std;
#endif
MulticopterAttitudeControlSim::MulticopterAttitudeControlSim()
{
/* setup standard gains */
//XXX: make these configurable
_params.att_p(0) = 5.0;
_params.rate_p(0) = 0.05;
_params.rate_i(0) = 0.0;
_params.rate_d(0) = 0.003;
/* pitch gains */
_params.att_p(1) = 5.0;
_params.rate_p(1) = 0.05;
_params.rate_i(1) = 0.0;
_params.rate_d(1) = 0.003;
/* yaw gains */
_params.att_p(2) = 2.8;
_params.rate_p(2) = 0.2;
_params.rate_i(2) = 0.1;
_params.rate_d(2) = 0.0;
_params.yaw_rate_max = 0.5;
_params.yaw_ff = 0.5;
_params.man_roll_max = 0.6;
_params.man_pitch_max = 0.6;
_params.man_yaw_max = 0.6;
}
MulticopterAttitudeControlSim::~MulticopterAttitudeControlSim()
{
}
void MulticopterAttitudeControlSim::set_attitude(const Eigen::Quaternion<double> attitude)
{
math::Quaternion quat;
quat(0) = (float)attitude.w();
quat(1) = (float)attitude.x();
quat(2) = (float)attitude.y();
quat(3) = (float)attitude.z();
_v_att.q[0] = quat(0);
_v_att.q[1] = quat(1);
_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);
_v_att.R_valid = true;
}
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)
{
_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;
// 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);
}
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];
motor_inputs(3) = _actuators.control[3];
}
#ifndef MC_ATT_CONTROL_BASE_H_
#define MC_ATT_CONTROL_BASE_H_
/* Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_sim.h
*
* MC Attitude Controller Interface for usage in a simulator
*
* @author Roman Bapst <bapstr@ethz.ch>
*
*/
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <math.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/actuator_armed.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <lib/mathlib/mathlib.h>
#inlcude "mc_att_control_base.h"
#define YAW_DEADZONE 0.05f
#define MIN_TAKEOFF_THRUST 0.2f
#define RATES_I_LIMIT 0.3f
class MulticopterAttitudeControlSim :
public MulticopterAttitudeControlBase
{
public:
/**
* Constructor
*/
MulticopterAttitudeControlSim();
/**
* Destructor
*/
~MulticopterAttitudeControlSim();
/* setters and getters for interface with rotors-gazebo simulator */
void set_attitude(const Eigen::Quaternion<double> 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);
protected:
void vehicle_attitude_setpoint_poll() {}
};
#endif /* MC_ATT_CONTROL_BASE_H_ */
/****************************************************************************
*
* Copyright (C) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_att_control_m_start_nuttx.cpp
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
#include <px4_tasks.h>
extern bool mc_att_control_thread_running;
int mc_att_control_daemon_task; /**< Handle of deamon task / thread */
namespace px4
{
bool mc_att_control_task_should_exit = false;
}
using namespace px4;
extern int mc_att_control_start_main(int argc, char **argv);
extern "C" __EXPORT int mc_att_control_m_main(int argc, char *argv[]);
int mc_att_control_m_main(int argc, char *argv[])
{
if (argc < 2) {
warnx("usage: mc_att_control_m {start|stop|status}");
return 1;
}
if (!strcmp(argv[1], "start")) {
if (mc_att_control_thread_running) {
warnx("already running");
/* this is not an error */
return 0;
}
mc_att_control_task_should_exit = false;
warnx("ok now btak running");
mc_att_control_daemon_task = px4_task_spawn_cmd("mc_att_control_m",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1900,
mc_att_control_start_main,
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
return 0;
}
if (!strcmp(argv[1], "stop")) {
mc_att_control_task_should_exit = true;
return 0;
}
if (!strcmp(argv[1], "status")) {
if (mc_att_control_thread_running) {
warnx("is running");
} else {
warnx("not started");
}
return 0;
}
warnx("unrecognized command");
return 1;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment