fw_controller testing

This commit is contained in:
Thomas Gubler 2012-11-25 18:20:54 +01:00
parent dd05426002
commit 4366d9e319
5 changed files with 46 additions and 19 deletions

View File

@ -146,13 +146,16 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
/* Roll (P) */ /* Roll (P) */
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0); rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0);
/* Pitch (P) */ /* Pitch (P) */
float pitch_sp_rollcompensation = att_sp->pitch_body + p.pitch_roll_compensation_p * att_sp->roll_body; float pitch_sp_rollcompensation = att_sp->pitch_body + p.pitch_roll_compensation_p * att_sp->roll_body;
rates_sp->pitch = pid_calculate(&pitch_controller, pitch_sp_rollcompensation, att->pitch, 0, 0); rates_sp->pitch = pid_calculate(&pitch_controller, pitch_sp_rollcompensation, att->pitch, 0, 0);
/* Yaw (from coordinated turn constraint or lateral force) */ /* Yaw (from coordinated turn constraint or lateral force) */
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)) 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)); / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[2] * sinf(att->pitch));
// printf("rates_sp->yaw %.4f \n", (double)rates_sp->yaw);
counter++; counter++;

View File

@ -230,8 +230,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
//REMOVEME XXX //REMOVEME XXX
actuators.control[3] = 0.7f; actuators.control[3] = 0.7f;
// debug_output.value = rates_sp.pitch; debug_output.value = rates_sp.pitch;
// orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output); orb_publish(ORB_ID(debug_key_value), debug_pub, &debug_output);
} else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
/* directly pass through values */ /* directly pass through values */
actuators.control[0] = manual_sp.roll; actuators.control[0] = manual_sp.roll;

View File

@ -169,10 +169,8 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
/* Roll Rate (PI) */ /* 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, deltaT);
actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT);
actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT);
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] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
counter++; counter++;

View File

@ -66,10 +66,13 @@
* Controller parameters, accessible via MAVLink * Controller parameters, accessible via MAVLink
* *
*/ */
PARAM_DEFINE_FLOAT(FW_HEADING_P, 0.1f); PARAM_DEFINE_FLOAT(FW_HEAD_P, 0.1f);
PARAM_DEFINE_FLOAT(FW_HEADR_I, 0.1f);
PARAM_DEFINE_FLOAT(FW_HEADR_LIM, 1.5f); //TODO: think about reasonable value
PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track
PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f); PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f);
PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians
PARAM_DEFINE_FLOAT(FW_HEADR_P, 0.1f);
PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); // Pitch angle limit in radians
@ -77,6 +80,7 @@ struct fw_pos_control_params {
float heading_p; float heading_p;
float headingr_p; float headingr_p;
float headingr_i; float headingr_i;
float headingr_lim;
float xtrack_p; float xtrack_p;
float altitude_p; float altitude_p;
float roll_lim; float roll_lim;
@ -87,6 +91,7 @@ struct fw_pos_control_param_handles {
param_t heading_p; param_t heading_p;
param_t headingr_p; param_t headingr_p;
param_t headingr_i; param_t headingr_i;
param_t headingr_lim;
param_t xtrack_p; param_t xtrack_p;
param_t altitude_p; param_t altitude_p;
param_t roll_lim; param_t roll_lim;
@ -140,9 +145,10 @@ static int deamon_task; /**< Handle of deamon task / thread */
static int parameters_init(struct fw_pos_control_param_handles *h) static int parameters_init(struct fw_pos_control_param_handles *h)
{ {
/* PID parameters */ /* PID parameters */
h->heading_p = param_find("FW_HEADING_P"); h->heading_p = param_find("FW_HEAD_P");
h->headingr_p = param_find("FW_HEADINGR_P"); h->headingr_p = param_find("FW_HEADR_P");
h->headingr_i = param_find("FW_HEADINGR_I"); h->headingr_i = param_find("FW_HEADR_I");
h->headingr_lim = param_find("FW_HEADR_LIM");
h->xtrack_p = param_find("FW_XTRACK_P"); h->xtrack_p = param_find("FW_XTRACK_P");
h->altitude_p = param_find("FW_ALT_P"); h->altitude_p = param_find("FW_ALT_P");
h->roll_lim = param_find("FW_ROLL_LIM"); h->roll_lim = param_find("FW_ROLL_LIM");
@ -157,6 +163,7 @@ static int parameters_update(const struct fw_pos_control_param_handles *h, struc
param_get(h->heading_p, &(p->heading_p)); param_get(h->heading_p, &(p->heading_p));
param_get(h->headingr_p, &(p->headingr_p)); param_get(h->headingr_p, &(p->headingr_p));
param_get(h->headingr_i, &(p->headingr_i)); param_get(h->headingr_i, &(p->headingr_i));
param_get(h->headingr_lim, &(p->headingr_lim));
param_get(h->xtrack_p, &(p->xtrack_p)); param_get(h->xtrack_p, &(p->xtrack_p));
param_get(h->altitude_p, &(p->altitude_p)); param_get(h->altitude_p, &(p->altitude_p));
param_get(h->roll_lim, &(p->roll_lim)); param_get(h->roll_lim, &(p->roll_lim));
@ -239,7 +246,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
parameters_init(&h); parameters_init(&h);
parameters_update(&h, &p); parameters_update(&h, &p);
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_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(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 1.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE); //TODO: integrator limit
pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_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 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
initialized = true; initialized = true;
@ -250,7 +257,7 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
/* update parameters from storage */ /* update parameters from storage */
parameters_update(&h, &p); parameters_update(&h, &p);
pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit 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(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 1.0f, p.roll_lim); //TODO: integrator limit
pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_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 pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f*M_DEG_TO_RAD); //TODO: remove hardcoded value
@ -293,28 +300,47 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
if(!(distance_res != OK || xtrack_err.past_end)) { if(!(distance_res != OK || xtrack_err.past_end)) {
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 // printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance);
float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance
// printf("delta_psi_c %.4f ", (double)delta_psi_c);
float psi_c = psi_track + delta_psi_c; float psi_c = psi_track + delta_psi_c;
// printf("psi_c %.4f ", (double)psi_c);
// printf("att.yaw %.4f ", (double)att.yaw);
float psi_e = psi_c - att.yaw; float psi_e = psi_c - att.yaw;
// printf("psi_e %.4f ", (double)psi_e);
/* shift error to prevent wrapping issues */ /* shift error to prevent wrapping issues */
psi_e = _wrap_pi(psi_e); psi_e = _wrap_pi(psi_e);
/* calculate roll setpoint, do this artificially around zero */ /* calculate roll setpoint, do this artificially around zero */
//TODO: psi rate loop incomplete
float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f); 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_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; float psi_rate_c = delta_psi_rate_c + psi_rate_track;
//TODO limit turn rate //limit turn rate
if(psi_rate_c > p.headingr_lim)
psi_rate_c = p.headingr_lim;
else if(psi_rate_c < -p.headingr_lim)
psi_rate_c = - p.headingr_lim;
// printf("psi_rate_c %.4f ", (double)psi_rate_c);
float psi_rate_e = psi_rate_c - att.yawspeed; 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 float psi_rate_e_scaled = psi_rate_e * sqrtf(powf(global_pos.vx, 2.0f) + powf(global_pos.vy, 2.0f)) / 9.81f; //* V_gr / g
attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT); // printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled);
attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);\
// printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body);
// if (counter % 100 == 0) // if (counter % 100 == 0)
// printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c); // printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c);

View File

@ -300,7 +300,7 @@ handle_message(mavlink_message_t *msg)
//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 //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) { if(mavlink_system.type == MAV_TYPE_FIXED_WING) {
//TODO: asuming low pitch and roll for now //TODO: assuming low pitch and roll values for now
hil_attitude.R[0][0] = cosf(hil_state.yaw); hil_attitude.R[0][0] = cosf(hil_state.yaw);
hil_attitude.R[0][1] = sinf(hil_state.yaw); hil_attitude.R[0][1] = sinf(hil_state.yaw);
hil_attitude.R[0][2] = 0.0f; hil_attitude.R[0][2] = 0.0f;