mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
Reworking control infrastructure for inner rate loop, preparing offboard interface
This commit is contained in:
@@ -501,6 +501,8 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c
|
||||
int old_mode = current_status->flight_mode;
|
||||
current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
|
||||
current_status->flag_control_manual_enabled = true;
|
||||
/* enable attitude control per default */
|
||||
current_status->flag_control_attitude_enabled = true;
|
||||
if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
|
||||
|
||||
if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
|
||||
|
||||
@@ -83,7 +83,7 @@
|
||||
/* define MAVLink specific parameters */
|
||||
PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
|
||||
PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
|
||||
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_GENERIC);
|
||||
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_QUADROTOR);
|
||||
|
||||
__EXPORT int mavlink_main(int argc, char *argv[]);
|
||||
int mavlink_thread_main(int argc, char *argv[]);
|
||||
@@ -95,7 +95,7 @@ static int mavlink_task;
|
||||
/* terminate MAVLink on user request - disabled by default */
|
||||
static bool mavlink_link_termination_allowed = false;
|
||||
|
||||
mavlink_system_t mavlink_system = {100, 50, MAV_TYPE_FIXED_WING, 0, 0, 0}; // System ID, 1-255, Component/Subsystem ID, 1-255
|
||||
mavlink_system_t mavlink_system = {100, 50, MAV_TYPE_QUADROTOR, 0, 0, 0}; // System ID, 1-255, Component/Subsystem ID, 1-255
|
||||
static uint8_t chan = MAVLINK_COMM_0;
|
||||
static mavlink_status_t status;
|
||||
|
||||
@@ -1093,6 +1093,8 @@ static void *uorb_receiveloop(void *arg)
|
||||
/* --- DEBUG KEY/VALUE --- */
|
||||
if (fds[ifds++].revents & POLLIN) {
|
||||
orb_copy(ORB_ID(debug_key_value), subs->debug_key_value, &buf.debug);
|
||||
/* Enforce null termination */
|
||||
buf.debug.key[sizeof(buf.debug.key) - 1] = '\0';
|
||||
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, last_sensor_timestamp / 1000, buf.debug.key, buf.debug.value);
|
||||
}
|
||||
}
|
||||
@@ -1234,26 +1236,36 @@ void handleMessage(mavlink_message_t *msg)
|
||||
|
||||
/* Handle quadrotor motor setpoints */
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT) {
|
||||
mavlink_set_quad_motors_setpoint_t quad_motors_setpoint;
|
||||
mavlink_msg_set_quad_motors_setpoint_decode(msg, &quad_motors_setpoint);
|
||||
if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) {
|
||||
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
|
||||
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
|
||||
// printf("got MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT target_system=%u, sysid = %u\n", quad_motors_setpoint.target_system, mavlink_system.sysid);
|
||||
|
||||
if (quad_motors_setpoint.target_system == mavlink_system.sysid) {
|
||||
ardrone_motors.motor_front_nw = quad_motors_setpoint.motor_front_nw;
|
||||
ardrone_motors.motor_right_ne = quad_motors_setpoint.motor_right_ne;
|
||||
ardrone_motors.motor_back_se = quad_motors_setpoint.motor_back_se;
|
||||
ardrone_motors.motor_left_sw = quad_motors_setpoint.motor_left_sw;
|
||||
if (mavlink_system.sysid < 4) {
|
||||
ardrone_motors.p1 = quad_motors_setpoint.roll[mavlink_system.sysid];
|
||||
ardrone_motors.p2 = quad_motors_setpoint.pitch[mavlink_system.sysid];
|
||||
ardrone_motors.p3 = quad_motors_setpoint.yaw[mavlink_system.sysid];
|
||||
ardrone_motors.p4 = quad_motors_setpoint.thrust[mavlink_system.sysid];
|
||||
|
||||
ardrone_motors.counter++;
|
||||
ardrone_motors.timestamp = hrt_absolute_time();
|
||||
|
||||
/* check if topic has to be advertised */
|
||||
if (ardrone_motors_pub <= 0) {
|
||||
ardrone_motors_pub = orb_advertise(ORB_ID(ardrone_motors_setpoint), &ardrone_motors);
|
||||
/* only send if RC is off */
|
||||
if (v_status.rc_signal_lost) {
|
||||
/* check if input has to be enabled */
|
||||
if (!v_status.flag_control_offboard_enabled) {
|
||||
/* XXX Enable offboard control */
|
||||
}
|
||||
|
||||
/* XXX decode mode and set flags */
|
||||
// if (mode == abc) xxx flag_control_rates_enabled;
|
||||
|
||||
/* check if topic has to be advertised */
|
||||
if (ardrone_motors_pub <= 0) {
|
||||
ardrone_motors_pub = orb_advertise(ORB_ID(ardrone_motors_setpoint), &ardrone_motors);
|
||||
}
|
||||
/* Publish */
|
||||
orb_publish(ORB_ID(ardrone_motors_setpoint), ardrone_motors_pub, &ardrone_motors);
|
||||
}
|
||||
/* Publish */
|
||||
orb_publish(ORB_ID(ardrone_motors_setpoint), ardrone_motors_pub, &ardrone_motors);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1557,8 +1569,6 @@ int mavlink_thread_main(int argc, char *argv[])
|
||||
mavlink_wpm_init(wpm);
|
||||
|
||||
uint16_t counter = 0;
|
||||
/* arm counter to go off immediately */
|
||||
int lowspeed_counter = 10;
|
||||
|
||||
/* make sure all threads have registered their subscriptions */
|
||||
while (!mavlink_subs.initialized) {
|
||||
@@ -1625,6 +1635,9 @@ int mavlink_thread_main(int argc, char *argv[])
|
||||
|
||||
thread_running = true;
|
||||
|
||||
/* arm counter to go off immediately */
|
||||
int lowspeed_counter = 10;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
|
||||
/* get local and global position */
|
||||
@@ -1649,7 +1662,7 @@ int mavlink_thread_main(int argc, char *argv[])
|
||||
|
||||
int32_t system_type;
|
||||
param_get(param_system_type, &system_type);
|
||||
if (system_type >= 0 && system_type < MAV_AUTOPILOT_ENUM_END) {
|
||||
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
|
||||
mavlink_system.type = system_type;
|
||||
}
|
||||
|
||||
@@ -1659,7 +1672,7 @@ int mavlink_thread_main(int argc, char *argv[])
|
||||
get_mavlink_mode_and_state(&v_status, &armed, &mavlink_state, &mavlink_mode);
|
||||
|
||||
/* send heartbeat */
|
||||
mavlink_msg_heartbeat_send(chan, system_type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
|
||||
mavlink_msg_heartbeat_send(chan, mavlink_system.type, MAV_AUTOPILOT_PX4, mavlink_mode, v_status.state_machine, mavlink_state);
|
||||
|
||||
/* switch HIL mode if required */
|
||||
set_hil_on_off(v_status.flag_hil_enabled);
|
||||
|
||||
@@ -32,7 +32,7 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
/**
|
||||
* @file multirotor_att_control_main.c
|
||||
*
|
||||
* Implementation of multirotor attitude control main loop.
|
||||
@@ -103,6 +103,8 @@ mc_thread_main(int argc, char *argv[])
|
||||
int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
||||
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
int setpoint_sub = orb_subscribe(ORB_ID(ardrone_motors_setpoint));
|
||||
|
||||
/*
|
||||
* Do not rate-limit the loop to prevent aliasing
|
||||
@@ -143,28 +145,49 @@ mc_thread_main(int argc, char *argv[])
|
||||
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
|
||||
/* get a local copy of attitude setpoint */
|
||||
orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp);
|
||||
/* get a local copy of the current sensor values */
|
||||
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
|
||||
|
||||
att_sp.roll_body = manual.roll;
|
||||
att_sp.pitch_body = manual.pitch;
|
||||
att_sp.yaw_rate_body = manual.yaw;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
if (motor_test_mode) {
|
||||
att_sp.roll_body = 0.0f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
att_sp.yaw_body = 0.0f;
|
||||
att_sp.roll_rate_body = 0.0f;
|
||||
att_sp.pitch_rate_body = 0.0f;
|
||||
att_sp.yaw_rate_body = 0.0f;
|
||||
att_sp.thrust = 0.1f;
|
||||
} else {
|
||||
att_sp.thrust = manual.throttle;
|
||||
|
||||
/** STEP 1: Define which input is the dominating control input */
|
||||
|
||||
if (state.flag_control_manual_enabled) {
|
||||
/* manual inputs, from RC control or joystick */
|
||||
att_sp.roll_body = manual.roll;
|
||||
att_sp.pitch_body = manual.pitch;
|
||||
att_sp.yaw_rate_body = manual.yaw;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
if (motor_test_mode) {
|
||||
att_sp.roll_body = 0.0f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
att_sp.yaw_body = 0.0f;
|
||||
att_sp.roll_rate_body = 0.0f;
|
||||
att_sp.pitch_rate_body = 0.0f;
|
||||
att_sp.yaw_rate_body = 0.0f;
|
||||
att_sp.thrust = 0.1f;
|
||||
} else {
|
||||
att_sp.thrust = manual.throttle;
|
||||
}
|
||||
} else if (state.flag_control_offboard_enabled) {
|
||||
/* offboard inputs */
|
||||
|
||||
/* decide wether we want rate or position input */
|
||||
}
|
||||
|
||||
multirotor_control_attitude(&att_sp, &att, &actuators);
|
||||
/** STEP 2: Identify the controller setup to run and set up the inputs correctly */
|
||||
|
||||
/* publish the result */
|
||||
/* run attitude controller */
|
||||
if (state.flag_control_attitude_enabled) {
|
||||
multirotor_control_attitude(&att_sp, &att, &actuators);
|
||||
}
|
||||
|
||||
/* XXX could be also run in an independent loop */
|
||||
if (state.flag_control_rates_enabled) {
|
||||
multirotor_control_rates(&att_sp, &raw.gyro_rad_s, &actuators);
|
||||
}
|
||||
|
||||
/* STEP 3: publish the result to the vehicle actuators */
|
||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||
|
||||
|
||||
@@ -213,7 +213,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
|
||||
|
||||
// pid_init(&yaw_pos_controller, p.yaw_p, p.yaw_i, p.yaw_d, p.yaw_awu,
|
||||
// PID_MODE_DERIVATIV_SET, 154);
|
||||
pid_init(&yaw_speed_controller, p.yawrate_p, p.yawrate_d, p.yawrate_i, p.yawrate_awu,
|
||||
pid_init(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu,
|
||||
PID_MODE_DERIVATIV_SET, 155);
|
||||
pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
|
||||
PID_MODE_DERIVATIV_SET, 156);
|
||||
@@ -229,7 +229,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
|
||||
parameters_update(&h, &p);
|
||||
/* apply parameters */
|
||||
// pid_set_parameters(&yaw_pos_controller, p.yaw_p, p.yaw_i, p.yaw_d, p.yaw_awu);
|
||||
pid_set_parameters(&yaw_speed_controller, p.yawrate_p, p.yawrate_d, p.yawrate_i, p.yawrate_awu);
|
||||
pid_set_parameters(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu);
|
||||
pid_set_parameters(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu);
|
||||
pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, p.att_awu);
|
||||
}
|
||||
|
||||
256
apps/multirotor_att_control/multirotor_rate_control.c
Normal file
256
apps/multirotor_att_control/multirotor_rate_control.c
Normal file
@@ -0,0 +1,256 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 multirotor_rate_control.c
|
||||
* Implementation of rate controller
|
||||
*/
|
||||
|
||||
#include "multirotor_rate_control.h"
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <float.h>
|
||||
#include <math.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <arch/board/up_hrt.h>
|
||||
|
||||
// PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.08f); /* same on Flamewheel */
|
||||
// PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.02f);
|
||||
// PARAM_DEFINE_FLOAT(MC_YAWRATE_AWU, 0.02f);
|
||||
// PARAM_DEFINE_FLOAT(MC_YAWRATE_LIM, 0.1f);
|
||||
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.2f); /* 0.15 F405 Flamewheel */
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_AWU, 0.05f);
|
||||
PARAM_DEFINE_FLOAT(MC_ATTRATE_LIM, 8.0f); /**< roughly < 500 deg/s limit */
|
||||
|
||||
struct mc_rate_control_params {
|
||||
|
||||
float yawrate_p;
|
||||
float yawrate_i;
|
||||
float yawrate_awu;
|
||||
float yawrate_lim;
|
||||
|
||||
float attrate_p;
|
||||
float attrate_i;
|
||||
float attrate_awu;
|
||||
float attrate_lim;
|
||||
|
||||
float rate_lim;
|
||||
};
|
||||
|
||||
struct mc_rate_control_param_handles {
|
||||
|
||||
param_t yawrate_p;
|
||||
param_t yawrate_i;
|
||||
param_t yawrate_awu;
|
||||
param_t yawrate_lim;
|
||||
|
||||
param_t attrate_p;
|
||||
param_t attrate_i;
|
||||
param_t attrate_awu;
|
||||
param_t attrate_lim;
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
*/
|
||||
static int parameters_init(struct mc_rate_control_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
static int parameters_update(const struct mc_rate_control_param_handles *h, struct mc_rate_control_params *p);
|
||||
|
||||
|
||||
static int parameters_init(struct mc_rate_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->yawrate_p = param_find("MC_YAWRATE_P");
|
||||
h->yawrate_i = param_find("MC_YAWRATE_I");
|
||||
h->yawrate_awu = param_find("MC_YAWRATE_AWU");
|
||||
h->yawrate_lim = param_find("MC_YAWRATE_LIM");
|
||||
|
||||
h->attrate_p = param_find("MC_ATTRATE_P");
|
||||
h->attrate_i = param_find("MC_ATTRATE_I");
|
||||
h->attrate_awu = param_find("MC_ATTRATE_AWU");
|
||||
h->attrate_lim = param_find("MC_ATTRATE_LIM");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int parameters_update(const struct mc_rate_control_param_handles *h, struct mc_rate_control_params *p)
|
||||
{
|
||||
param_get(h->yawrate_p, &(p->yawrate_p));
|
||||
param_get(h->yawrate_i, &(p->yawrate_i));
|
||||
param_get(h->yawrate_awu, &(p->yawrate_awu));
|
||||
param_get(h->yawrate_lim, &(p->yawrate_lim));
|
||||
|
||||
param_get(h->attrate_p, &(p->attrate_p));
|
||||
param_get(h->attrate_i, &(p->attrate_i));
|
||||
param_get(h->attrate_awu, &(p->attrate_awu));
|
||||
param_get(h->attrate_lim, &(p->attrate_lim));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void multirotor_control_rates(const struct vehicle_attitude_setpoint_s *rate_sp,
|
||||
const float rates[], struct actuator_controls_s *actuators)
|
||||
{
|
||||
static uint64_t last_run = 0;
|
||||
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
||||
last_run = hrt_absolute_time();
|
||||
|
||||
static int motor_skip_counter = 0;
|
||||
|
||||
// static PID_t yaw_pos_controller;
|
||||
static PID_t yaw_speed_controller;
|
||||
static PID_t pitch_controller;
|
||||
static PID_t roll_controller;
|
||||
|
||||
static struct mc_rate_control_params p;
|
||||
static struct mc_rate_control_param_handles h;
|
||||
|
||||
static bool initialized = false;
|
||||
|
||||
/* initialize the pid controllers when the function is called for the first time */
|
||||
if (initialized == false) {
|
||||
parameters_init(&h);
|
||||
parameters_update(&h, &p);
|
||||
|
||||
pid_init(&yaw_speed_controller, p.yawrate_p, 0, p.yawrate_i, p.yawrate_awu,
|
||||
PID_MODE_DERIVATIV_SET, 155);
|
||||
pid_init(&pitch_controller, p.attrate_p, p.attrate_i, 0, p.attrate_awu,
|
||||
PID_MODE_DERIVATIV_SET, 156);
|
||||
pid_init(&roll_controller, p.attrate_p, p.attrate_i, 0, p.attrate_awu,
|
||||
PID_MODE_DERIVATIV_SET, 157);
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
/* load new parameters with lower rate */
|
||||
if (motor_skip_counter % 250 == 0) {
|
||||
/* update parameters from storage */
|
||||
parameters_update(&h, &p);
|
||||
/* apply parameters */
|
||||
pid_set_parameters(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu);
|
||||
pid_set_parameters(&pitch_controller, p.attrate_p, p.attrate_i, 0, p.attrate_awu);
|
||||
pid_set_parameters(&roll_controller, p.attrate_p, p.attrate_i, 0, p.attrate_awu);
|
||||
}
|
||||
|
||||
/* calculate current control outputs */
|
||||
|
||||
/* control pitch (forward) output */
|
||||
float pitch_control = pid_calculate(&pitch_controller, rate_sp->pitch_rate_body,
|
||||
rates[1], 0.0f, deltaT);
|
||||
/* control roll (left/right) output */
|
||||
float roll_control = pid_calculate(&roll_controller, rate_sp->roll_rate_body,
|
||||
rates[0], 0.0f, deltaT);
|
||||
/* control yaw rate */
|
||||
float yaw_rate_control = pid_calculate(&yaw_speed_controller, rate_sp->yaw_rate_body, rates[2], 0.0f, deltaT);
|
||||
|
||||
/*
|
||||
* compensate the vertical loss of thrust
|
||||
* when thrust plane has an angle.
|
||||
* start with a factor of 1.0 (no change)
|
||||
*/
|
||||
float zcompensation = 1.0f;
|
||||
|
||||
// if (fabsf(att->roll) > 0.3f) {
|
||||
// zcompensation *= 1.04675160154f;
|
||||
|
||||
// } else {
|
||||
// zcompensation *= 1.0f / cosf(att->roll);
|
||||
// }
|
||||
|
||||
// if (fabsf(att->pitch) > 0.3f) {
|
||||
// zcompensation *= 1.04675160154f;
|
||||
|
||||
// } else {
|
||||
// zcompensation *= 1.0f / cosf(att->pitch);
|
||||
// }
|
||||
|
||||
float motor_thrust = 0.0f;
|
||||
|
||||
motor_thrust = rate_sp->thrust;
|
||||
|
||||
/* compensate thrust vector for roll / pitch contributions */
|
||||
motor_thrust *= zcompensation;
|
||||
|
||||
/* limit yaw rate output */
|
||||
if (yaw_rate_control > p.yawrate_lim) {
|
||||
yaw_rate_control = p.yawrate_lim;
|
||||
yaw_speed_controller.saturated = 1;
|
||||
}
|
||||
|
||||
if (yaw_rate_control < -p.yawrate_lim) {
|
||||
yaw_rate_control = -p.yawrate_lim;
|
||||
yaw_speed_controller.saturated = 1;
|
||||
}
|
||||
|
||||
if (pitch_control > p.attrate_lim) {
|
||||
pitch_control = p.attrate_lim;
|
||||
pitch_controller.saturated = 1;
|
||||
}
|
||||
|
||||
if (pitch_control < -p.attrate_lim) {
|
||||
pitch_control = -p.attrate_lim;
|
||||
pitch_controller.saturated = 1;
|
||||
}
|
||||
|
||||
|
||||
if (roll_control > p.attrate_lim) {
|
||||
roll_control = p.attrate_lim;
|
||||
roll_controller.saturated = 1;
|
||||
}
|
||||
|
||||
if (roll_control < -p.attrate_lim) {
|
||||
roll_control = -p.attrate_lim;
|
||||
roll_controller.saturated = 1;
|
||||
}
|
||||
|
||||
actuators->control[0] = roll_control;
|
||||
actuators->control[1] = pitch_control;
|
||||
actuators->control[2] = yaw_rate_control;
|
||||
actuators->control[3] = motor_thrust;
|
||||
|
||||
motor_skip_counter++;
|
||||
}
|
||||
56
apps/multirotor_att_control/multirotor_rate_control.h
Normal file
56
apps/multirotor_att_control/multirotor_rate_control.h
Normal file
@@ -0,0 +1,56 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Laurens Mackay <mackayl@student.ethz.ch>
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Martin Rutschmann <rutmarti@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 multirotor_attitude_control.h
|
||||
* Attitude control for multi rotors.
|
||||
*/
|
||||
|
||||
#ifndef MULTIROTOR_RATE_CONTROL_H_
|
||||
#define MULTIROTOR_RATE_CONTROL_H_
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
void multirotor_control_rates(const struct vehicle_attitude_setpoint_s *rate_sp,
|
||||
const float rates[], struct actuator_controls_s *actuators);
|
||||
|
||||
#endif /* MULTIROTOR_RATE_CONTROL_H_ */
|
||||
@@ -40,9 +40,14 @@
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
|
||||
|
||||
static bool thread_should_exit = false; /**< ground_estimator exit flag */
|
||||
static bool thread_running = false; /**< ground_estimator status flag */
|
||||
@@ -51,7 +56,7 @@ static int ground_estimator_task; /**< Handle of ground_estimator task / thre
|
||||
/**
|
||||
* ground_estimator management function.
|
||||
*/
|
||||
__EXPORT int ground_estimator_app_main(int argc, char *argv[]);
|
||||
__EXPORT int ground_estimator_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of ground_estimator.
|
||||
@@ -69,17 +74,20 @@ int ground_estimator_thread_main(int argc, char *argv[]) {
|
||||
|
||||
/* subscribe to raw data */
|
||||
int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
|
||||
bool publishing = false;
|
||||
|
||||
/* advertise attitude */
|
||||
struct debug_key_value_s dbg = { .key = "velx ", .value = 0.0f };
|
||||
orb_advert_t pub_att = orb_advertise(ORB_ID(debug_key_value), &dbg);
|
||||
struct debug_key_value_s dbg = { .key = "posx", .value = 0.0f };
|
||||
orb_advert_t pub_dbg = orb_advertise(ORB_ID(debug_key_value), &dbg);
|
||||
|
||||
float position[3] = {};
|
||||
float velocity[3] = {};
|
||||
|
||||
uint64_t last_time = 0;
|
||||
|
||||
struct pollfd fds[] = {
|
||||
{ .fd = sub_raw, .events = POLLIN },
|
||||
};
|
||||
|
||||
while (!thread_should_exit) {
|
||||
|
||||
/* wait for sensor update */
|
||||
@@ -94,16 +102,16 @@ int ground_estimator_thread_main(int argc, char *argv[]) {
|
||||
struct sensor_combined_s s;
|
||||
orb_copy(ORB_ID(sensor_combined), sub_raw, &s);
|
||||
|
||||
uint64_t dt = s.timestamp - last_time;
|
||||
float dt = ((float)(s.timestamp - last_time)) / 1000000.0f;
|
||||
|
||||
/* Integration */
|
||||
position[0] += velocity[0] * dt;
|
||||
position[1] += velocity[1] * dt;
|
||||
position[2] += velocity[2] * dt;
|
||||
|
||||
velocity[0] += velocity[0] * 0.01f + 0.99f * s.acceleration_m_s2[0] * dt;
|
||||
velocity[1] += velocity[1] * 0.01f + 0.99f * s.acceleration_m_s2[1] * dt;
|
||||
velocity[2] += velocity[2] * 0.01f + 0.99f * s.acceleration_m_s2[2] * dt;
|
||||
velocity[0] += velocity[0] * 0.01f + 0.99f * s.accelerometer_m_s2[0] * dt;
|
||||
velocity[1] += velocity[1] * 0.01f + 0.99f * s.accelerometer_m_s2[1] * dt;
|
||||
velocity[2] += velocity[2] * 0.01f + 0.99f * s.accelerometer_m_s2[2] * dt;
|
||||
|
||||
dbg.value = position[0];
|
||||
|
||||
@@ -134,7 +142,7 @@ usage(const char *reason)
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int ground_estimator_app_main(int argc, char *argv[])
|
||||
int ground_estimator_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
@@ -50,14 +50,14 @@
|
||||
|
||||
struct ardrone_motors_setpoint_s
|
||||
{
|
||||
uint16_t counter; //incremented by the writing thread everytime new data is stored
|
||||
uint64_t timestamp; //in microseconds since system start, is set whenever the writing thread stores new data
|
||||
|
||||
uint16_t motor_front_nw; ///< Front motor in + configuration, front left motor in x configuration
|
||||
uint16_t motor_right_ne; ///< Right motor in + configuration, front right motor in x configuration
|
||||
uint16_t motor_back_se; ///< Back motor in + configuration, back right motor in x configuration
|
||||
uint16_t motor_left_sw; ///< Left motor in + configuration, back left motor in x configuration
|
||||
|
||||
uint8_t group; /**< quadrotor group */
|
||||
uint8_t mode; /**< requested flight mode XXX define */
|
||||
float p1; /**< parameter 1: rate control: roll rate, att control: roll angle (in radians, NED) */
|
||||
float p2; /**< parameter 2: rate control: pitch rate, att control: pitch angle (in radians, NED) */
|
||||
float p3; /**< parameter 3: rate control: yaw rate, att control: yaw angle (in radians, NED) */
|
||||
float p4; /**< parameter 4: thrust, [0..1] */
|
||||
}; /**< AR.Drone low level motors */
|
||||
|
||||
/**
|
||||
|
||||
@@ -111,23 +111,24 @@ struct vehicle_status_s
|
||||
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
|
||||
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
|
||||
|
||||
commander_state_machine_t state_machine; /**< Current flight state, main state machine */
|
||||
enum VEHICLE_FLIGHT_MODE flight_mode; /**< Current flight mode, as defined by mode switch */
|
||||
enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< Current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
|
||||
commander_state_machine_t state_machine; /**< current flight state, main state machine */
|
||||
enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
|
||||
enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
|
||||
|
||||
// uint8_t mode;
|
||||
|
||||
|
||||
/* system flags - these represent the state predicates */
|
||||
|
||||
bool flag_system_armed; /**< True is motors / actuators are armed */
|
||||
bool flag_system_armed; /**< true is motors / actuators are armed */
|
||||
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
|
||||
bool flag_hil_enabled; /**< True if hardware in the loop simulation is enabled */
|
||||
bool flag_control_offboard_enabled; /**< true if offboard control input is on */
|
||||
bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
|
||||
|
||||
// bool flag_control_rates_enabled; /**< true if rates are stabilized */
|
||||
// bool flag_control_attitude_enabled; *< true if attitude stabilization is mixed in
|
||||
// bool control_speed_enabled; /**< true if speed (implies direction) is controlled */
|
||||
// bool control_position_enabled; /**< true if position is controlled */
|
||||
bool flag_control_rates_enabled; /**< true if rates are stabilized */
|
||||
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
|
||||
bool flag_control_speed_enabled; /**< true if speed (implies direction) is controlled */
|
||||
bool flag_control_position_enabled; /**< true if position is controlled */
|
||||
|
||||
bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
|
||||
bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
|
||||
|
||||
@@ -78,7 +78,7 @@ CONFIGURED_APPS += px4/attitude_estimator_bm
|
||||
CONFIGURED_APPS += fixedwing_control
|
||||
CONFIGURED_APPS += position_estimator
|
||||
CONFIGURED_APPS += attitude_estimator_ekf
|
||||
CONFIGURED_APPS += ground_estimator
|
||||
CONFIGURED_APPS += px4/ground_estimator
|
||||
|
||||
# Hacking tools
|
||||
#CONFIGURED_APPS += system/i2c
|
||||
|
||||
Reference in New Issue
Block a user