forked from Archive/PX4-Autopilot
Merged fixed wing branches
This commit is contained in:
commit
80b84819d2
|
@ -146,6 +146,7 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
|
|||
/* Roll (P) */
|
||||
rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0);
|
||||
|
||||
|
||||
/* Pitch (P) */
|
||||
|
||||
/* compensate feedforward for loss of lift due to non-horizontal angle of wing */
|
||||
|
@ -156,7 +157,9 @@ int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att
|
|||
|
||||
/* 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))
|
||||
/ (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++;
|
||||
|
||||
|
|
|
@ -142,8 +142,6 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
memset(&manual_sp, 0, sizeof(manual_sp));
|
||||
struct vehicle_status_s vstatus;
|
||||
memset(&vstatus, 0, sizeof(vstatus));
|
||||
struct debug_key_value_s debug_output;
|
||||
memset(&debug_output, 0, sizeof(debug_output));
|
||||
|
||||
/* output structs */
|
||||
struct actuator_controls_s actuators;
|
||||
|
@ -156,8 +154,6 @@ 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);
|
||||
strncpy(debug_output.key, "yaw_rate", sizeof(debug_output.key - 1));
|
||||
|
||||
/* subscribe */
|
||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
|
@ -259,7 +255,6 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
|
||||
} else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
|
||||
/* directly pass through values */
|
||||
actuators.control[0] = manual_sp.roll;
|
||||
|
@ -269,10 +264,11 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
actuators.control[3] = manual_sp.throttle;
|
||||
}
|
||||
|
||||
/* publish output */
|
||||
/* publish rates */
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
|
||||
|
||||
/* publish actuator outputs */
|
||||
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");
|
||||
|
|
|
@ -169,9 +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.0f, deltaT);
|
||||
|
||||
/* pitch rate (PI) */
|
||||
actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
|
||||
/* yaw rate (PI) */
|
||||
|
|
|
@ -68,10 +68,13 @@
|
|||
* 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_ALT_P, 0.1f);
|
||||
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
|
||||
|
||||
|
||||
|
@ -79,6 +82,7 @@ struct fw_pos_control_params {
|
|||
float heading_p;
|
||||
float headingr_p;
|
||||
float headingr_i;
|
||||
float headingr_lim;
|
||||
float xtrack_p;
|
||||
float altitude_p;
|
||||
float roll_lim;
|
||||
|
@ -89,6 +93,7 @@ struct fw_pos_control_param_handles {
|
|||
param_t heading_p;
|
||||
param_t headingr_p;
|
||||
param_t headingr_i;
|
||||
param_t headingr_lim;
|
||||
param_t xtrack_p;
|
||||
param_t altitude_p;
|
||||
param_t roll_lim;
|
||||
|
@ -142,9 +147,10 @@ static int deamon_task; /**< Handle of deamon task / thread */
|
|||
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->heading_p = param_find("FW_HEAD_P");
|
||||
h->headingr_p = param_find("FW_HEADR_P");
|
||||
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->altitude_p = param_find("FW_ALT_P");
|
||||
h->roll_lim = param_find("FW_ROLL_LIM");
|
||||
|
@ -159,6 +165,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->headingr_p, &(p->headingr_p));
|
||||
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->altitude_p, &(p->altitude_p));
|
||||
param_get(h->roll_lim, &(p->roll_lim));
|
||||
|
@ -273,6 +280,11 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
|
|||
/* only run controller if attitude changed */
|
||||
if (fds[1].revents & POLLIN) {
|
||||
|
||||
|
||||
static uint64_t last_run = 0;
|
||||
const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
||||
last_run = hrt_absolute_time();
|
||||
|
||||
/* check if there is a new position or setpoint */
|
||||
bool pos_updated;
|
||||
orb_check(global_pos_sub, &pos_updated);
|
||||
|
@ -282,17 +294,17 @@ 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);
|
||||
}
|
||||
|
||||
if (global_sp_updated) {
|
||||
orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint);
|
||||
// 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);
|
||||
|
||||
start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint)
|
||||
global_sp_updated_set_once = true;
|
||||
|
@ -309,34 +321,53 @@ int fixedwing_pos_control_thread_main(int argc, char *argv[])
|
|||
|
||||
/* 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 = -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;
|
||||
|
||||
// printf("psi_c %.4f ", (double)psi_c);
|
||||
|
||||
// printf("att.yaw %.4f ", (double)att.yaw);
|
||||
|
||||
float psi_e = psi_c - att.yaw;
|
||||
|
||||
// printf("psi_e %.4f ", (double)psi_e);
|
||||
|
||||
/* shift error to prevent wrapping issues */
|
||||
psi_e = _wrap_pi(psi_e);
|
||||
|
||||
/* 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 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
|
||||
//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_scaled = psi_rate_e * sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy) / 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)
|
||||
// printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n",xtrack_err.distance, delta_psi_c);
|
||||
|
|
|
@ -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
|
||||
|
||||
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][1] = sinf(hil_state.yaw);
|
||||
hil_attitude.R[0][2] = 0.0f;
|
||||
|
|
Loading…
Reference in New Issue