aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.c6
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.h2
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_main.c51
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.c9
-rw-r--r--apps/fixedwing_pos_control/fixedwing_pos_control_main.c59
-rw-r--r--apps/mavlink/mavlink_receiver.c23
6 files changed, 117 insertions, 33 deletions
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c
index 045627700..a3c7df69d 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_att.c
+++ b/apps/fixedwing_att_control/fixedwing_att_control_att.c
@@ -113,6 +113,7 @@ static int parameters_update(const struct fw_pos_control_param_handles *h, struc
int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
const struct vehicle_attitude_s *att,
+ const float speed_body[],
struct vehicle_rates_setpoint_s *rates_sp)
{
static int counter = 0;
@@ -148,13 +149,14 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
/* Pitch (P) */
/* compensate feedforward for loss of lift due to non-horizontal angle of wing */
- float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(att_sp->roll_body);
+ float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(sinf(att_sp->roll_body));
/* set pitch plus feedforward roll compensation */
rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body + pitch_sp_rollcompensation,
att->pitch, 0, 0);
/* Yaw (from coordinated turn constraint or lateral force) */
- //TODO
+ rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll))
+ / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[1] * sinf(att->pitch));
counter++;
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.h b/apps/fixedwing_att_control/fixedwing_att_control_att.h
index ca7c14b43..11c932800 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_att.h
+++ b/apps/fixedwing_att_control/fixedwing_att_control_att.h
@@ -41,9 +41,11 @@
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_global_position.h>
int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
const struct vehicle_attitude_s *att,
+ const float speed_body[],
struct vehicle_rates_setpoint_s *rates_sp);
#endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/apps/fixedwing_att_control/fixedwing_att_control_main.c
index 9dd34b9ec..ee259f78c 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_main.c
+++ b/apps/fixedwing_att_control/fixedwing_att_control_main.c
@@ -58,6 +58,7 @@
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/debug_key_value.h>
#include <systemlib/param/param.h>
#include <systemlib/pid/pid.h>
@@ -135,13 +136,14 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
memset(&att_sp, 0, sizeof(att_sp));
struct vehicle_rates_setpoint_s rates_sp;
memset(&rates_sp, 0, sizeof(rates_sp));
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
struct manual_control_setpoint_s manual_sp;
memset(&manual_sp, 0, sizeof(manual_sp));
struct vehicle_status_s vstatus;
memset(&vstatus, 0, sizeof(vstatus));
-
-// static struct debug_key_value_s debug_output;
-// memset(&debug_output, 0, sizeof(debug_output));
+ struct debug_key_value_s debug_output;
+ memset(&debug_output, 0, sizeof(debug_output));
/* output structs */
struct actuator_controls_s actuators;
@@ -154,18 +156,19 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
}
orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
-// orb_advert_t debug_pub = orb_advertise(ORB_ID(debug_key_value), &debug_output);
-// debug_output.key[0] = '1';
-
+ orb_advert_t debug_pub = orb_advertise(ORB_ID(debug_key_value), &debug_output);
+ strncpy(debug_output.key, "yaw_rate", sizeof(debug_output.key - 1));
/* subscribe */
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
/* Setup of loop */
float gyro[3] = {0.0f, 0.0f, 0.0f};
+ float speed_body[3] = {0.0f, 0.0f, 0.0f};
struct pollfd fds = { .fd = att_sub, .events = POLLIN };
while(!thread_should_exit)
@@ -173,9 +176,35 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
/* wait for a sensor update, check for exit condition every 500 ms */
poll(&fds, 1, 500);
+ /* Check if there is a new position measurement or attitude setpoint */
+ bool pos_updated;
+ orb_check(global_pos_sub, &pos_updated);
+ bool att_sp_updated;
+ orb_check(att_sp_sub, &att_sp_updated);
+
/* get a local copy of attitude */
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
- orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
+ if(att_sp_updated)
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
+ if(pos_updated)
+ {
+ orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
+ if(att.R_valid)
+ {
+ speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz;
+ speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz;
+ speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz;
+ }
+ else
+ {
+ speed_body[0] = 0;
+ speed_body[1] = 0;
+ speed_body[2] = 0;
+
+ printf("FW ATT CONTROL: Did not get a valid R\n");
+ }
+ }
+
orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus);
@@ -184,10 +213,10 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
gyro[2] = att.yawspeed;
/* Control */
-
if (vstatus.state_machine == SYSTEM_STATE_AUTO) {
+
/* attitude control */
- fixedwing_att_control_attitude(&att_sp, &att, &rates_sp);
+ fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
/* publish rate setpoint */
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
@@ -219,7 +248,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
att_sp.timestamp = hrt_absolute_time();
}
- fixedwing_att_control_attitude(&att_sp, &att, &rates_sp);
+ fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
/* publish rate setpoint */
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
@@ -242,6 +271,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
/* publish output */
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
+ debug_output.value = rates_sp.yaw;
+ orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output);
}
printf("[fixedwing_att_control] exiting, stopping all motors.\n");
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
index f46761922..0bb54624f 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -170,11 +170,12 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
/* Roll Rate (PI) */
- actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0, deltaT);
+ actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT);
-
- actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT);
- actuators->control[2] = 0.0f;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
+ /* pitch rate (PI) */
+ actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
+ /* yaw rate (PI) */
+ actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT);
counter++;
diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
index d9acd8db9..45736aa2f 100644
--- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ b/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
@@ -77,6 +77,8 @@ PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians
struct fw_pos_control_params {
float heading_p;
+ float headingr_p;
+ float headingr_i;
float xtrack_p;
float altitude_p;
float roll_lim;
@@ -85,6 +87,8 @@ struct fw_pos_control_params {
struct fw_pos_control_param_handles {
param_t heading_p;
+ param_t headingr_p;
+ param_t headingr_i;
param_t xtrack_p;
param_t altitude_p;
param_t roll_lim;
@@ -139,6 +143,8 @@ static int parameters_init(struct fw_pos_control_param_handles *h)
{
/* PID parameters */
h->heading_p = param_find("FW_HEADING_P");
+ h->headingr_p = param_find("FW_HEADINGR_P");
+ h->headingr_i = param_find("FW_HEADINGR_I");
h->xtrack_p = param_find("FW_XTRACK_P");
h->altitude_p = param_find("FW_ALT_P");
h->roll_lim = param_find("FW_ROLL_LIM");
@@ -151,6 +157,8 @@ static int parameters_init(struct fw_pos_control_param_handles *h)
static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p)
{
param_get(h->heading_p, &(p->heading_p));
+ param_get(h->headingr_p, &(p->headingr_p));
+ param_get(h->headingr_i, &(p->headingr_i));
param_get(h->xtrack_p, &(p->xtrack_p));
param_get(h->altitude_p, &(p->altitude_p));
param_get(h->roll_lim, &(p->roll_lim));
@@ -221,12 +229,16 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
struct fw_pos_control_param_handles h;
PID_t heading_controller;
+ PID_t heading_rate_controller;
+ PID_t offtrack_controller;
PID_t altitude_controller;
parameters_init(&h);
parameters_update(&h, &p);
- pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f,p.roll_lim,PID_MODE_DERIVATIV_NONE);
- pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f,p.pitch_lim,PID_MODE_DERIVATIV_NONE);
+ pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE); //arbitrary high limit
+ pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE);
+ pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE);
+ pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f*M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE); //TODO: remove hardcoded value
/* error and performance monitoring */
perf_counter_t fw_interval_perf = perf_alloc(PC_INTERVAL, "fixedwing_pos_control_interval");
@@ -252,8 +264,10 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
/* update parameters from storage */
parameters_update(&h, &p);
- pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, p.roll_lim);
+ pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit
+ pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim);
pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim);
+ pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f*M_DEG_TO_RAD); //TODO: remove hardcoded value
}
/* only run controller if attitude changed */
@@ -268,6 +282,11 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
/* load local copies */
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+ static uint64_t last_run = 0;
+ const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+
if (pos_updated) {
orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
}
@@ -282,27 +301,21 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
printf("psi_track: %0.4f\n", (double)psi_track);
}
- /* simple horizontal control, execute if line between wps is known */
+ /* Simple Horizontal Control */
if(global_sp_updated_set_once)
{
// if (counter % 100 == 0)
// printf("lat_sp %d, ln_sp %d, lat: %d, lon: %d\n", global_setpoint.lat, global_setpoint.lon, global_pos.lat, global_pos.lon);
-
+
/* calculate crosstrack error */
// Only the case of a straight line track following handled so far
- int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
+ int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
(double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d,
(double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
if(!(distance_res != OK || xtrack_err.past_end)) {
- float delta_psi_c = -p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards
-
- if(delta_psi_c > 60.0f*M_DEG_TO_RAD_F)
- delta_psi_c = 60.0f*M_DEG_TO_RAD_F;
-
- if(delta_psi_c < -60.0f*M_DEG_TO_RAD_F)
- delta_psi_c = -60.0f*M_DEG_TO_RAD_F;
+ float delta_psi_c = -pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance; //(-) because z axis points downwards
float psi_c = psi_track + delta_psi_c;
@@ -312,7 +325,18 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
psi_e = _wrap_pi(psi_e);
/* calculate roll setpoint, do this artificially around zero */
- attitude_setpoint.roll_body = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
+ //TODO: psi rate loop incomplete
+ float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
+ float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following
+ float psi_rate_c = delta_psi_rate_c + psi_rate_track;
+
+ //TODO limit turn rate
+
+ float psi_rate_e = psi_rate_c - att.yawspeed;
+
+ float psi_rate_e_scaled = psi_rate_e * sqrtf(pow(global_pos.vx,2) + pow(global_pos.vy,2)) / 9.81f; //* V_gr / g
+
+ attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);
// if (counter % 100 == 0)
// printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c);
@@ -322,10 +346,13 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end);
}
- // XXX SIMPLE ALTITUDE, BUT NO SPEED CONTROL
- if (pos_updated) {
+ /* Very simple Altitude Control */
+ if(pos_updated)
+ {
+
//TODO: take care of relative vs. ab. altitude
attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f);
+
}
// XXX need speed control
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 6b4375445..e2f28dabd 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -296,6 +296,26 @@ handle_message(mavlink_message_t *msg)
mavlink_hil_state_t hil_state;
mavlink_msg_hil_state_decode(msg, &hil_state);
+ /* Calculate Rotation Matrix */
+ //TODO: better clarification which app does this, atm we have a ekf for quadrotors which does this, but there is no such thing if fly in fixed wing mode
+
+ if(mavlink_system.type == MAV_TYPE_FIXED_WING) {
+ //TODO: asuming low pitch and roll for now
+ hil_attitude.R[0][0] = cosf(hil_state.yaw);
+ hil_attitude.R[0][1] = sinf(hil_state.yaw);
+ hil_attitude.R[0][2] = 0.0f;
+
+ hil_attitude.R[1][0] = -sinf(hil_state.yaw);
+ hil_attitude.R[1][1] = cosf(hil_state.yaw);
+ hil_attitude.R[1][2] = 0.0f;
+
+ hil_attitude.R[2][0] = 0.0f;
+ hil_attitude.R[2][1] = 0.0f;
+ hil_attitude.R[2][2] = 1.0f;
+
+ hil_attitude.R_valid = true;
+ }
+
hil_global_pos.lat = hil_state.lat;
hil_global_pos.lon = hil_state.lon;
hil_global_pos.alt = hil_state.alt / 1000.0f;
@@ -303,6 +323,7 @@ handle_message(mavlink_message_t *msg)
hil_global_pos.vy = hil_state.vy / 100.0f;
hil_global_pos.vz = hil_state.vz / 100.0f;
+
/* set timestamp and notify processes (broadcast) */
hil_global_pos.timestamp = hrt_absolute_time();
orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
@@ -427,4 +448,4 @@ receive_start(int uart)
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
return thread;
-} \ No newline at end of file
+}