aboutsummaryrefslogtreecommitdiff
path: root/apps/fixedwing_att_control
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2012-11-11 19:10:26 +0100
committerThomas Gubler <thomasgubler@gmail.com>2012-11-13 20:24:23 +0100
commitc1e28f5f13beda2c3074e3c470293887d19d8071 (patch)
tree86e995160b38c4cf6bbae205d3d642adcbcc71e0 /apps/fixedwing_att_control
parent403874d313464c72da309483e6e8271e9c70f965 (diff)
downloadpx4-firmware-c1e28f5f13beda2c3074e3c470293887d19d8071.tar.gz
px4-firmware-c1e28f5f13beda2c3074e3c470293887d19d8071.tar.bz2
px4-firmware-c1e28f5f13beda2c3074e3c470293887d19d8071.zip
first version of yaw control loop, needs testing
Diffstat (limited to 'apps/fixedwing_att_control')
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.c4
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_att.h2
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_main.c46
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.c2
4 files changed, 45 insertions, 9 deletions
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/apps/fixedwing_att_control/fixedwing_att_control_att.c
index 18b290f99..24142dece 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;
@@ -150,7 +151,8 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
rates_sp->pitch = pid_calculate(&pitch_controller, 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 ad0f201e1..d2fbe31a6 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,28 +136,33 @@ 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));
-// static struct debug_key_value_s debug_output;
-// memset(&debug_output, 0, sizeof(debug_output));
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
+
/* output structs */
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
+ static struct debug_key_value_s debug_output;
+ memset(&debug_output, 0, sizeof(debug_output));
/* publish actuator controls */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
actuators.control[i] = 0.0f;
orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
-// 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);
+ debug_output.key[0] = '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));
/* 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)
@@ -164,10 +170,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 Local Copies */
/* 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");
+ }
+ }
gyro[0] = att.rollspeed;
gyro[1] = att.pitchspeed;
@@ -178,6 +209,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
/* Attitude Control */
fixedwing_att_control_attitude(&att_sp,
&att,
+ &speed_body,
&rates_sp);
/* Attitude Rate Control */
@@ -187,8 +219,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
actuators.control[3] = 0.7f;
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
-// debug_output.value = rates_sp.pitch;
-// orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output);
+ 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 b81d50168..6f3a7f6e8 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -172,7 +172,7 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); //TODO: (-) sign comes from the elevator (positive --> deflection downwards), this has to be moved to the mixer...
- actuators->control[2] = 0;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
+ actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
counter++;