|
|
@ -14,18 +14,19 @@ |
|
|
|
//Runs the main loiter controller
|
|
|
|
//Runs the main loiter controller
|
|
|
|
void ModeLoiter::run() |
|
|
|
void ModeLoiter::run() |
|
|
|
{ |
|
|
|
{ |
|
|
|
float pilot_fwd = channel_front->get_control_in() / float(RC_SCALE) * g.max_pos_xy * blimp.scheduler.get_loop_period_s(); |
|
|
|
Vector3f pilot; |
|
|
|
float pilot_rgt = channel_right->get_control_in() / float(RC_SCALE) * g.max_pos_xy * blimp.scheduler.get_loop_period_s(); |
|
|
|
pilot.x = channel_front->get_control_in() / float(RC_SCALE) * g.max_pos_xy * blimp.scheduler.get_loop_period_s(); |
|
|
|
float pilot_dwn = channel_down->get_control_in() / float(RC_SCALE) * g.max_pos_z * blimp.scheduler.get_loop_period_s(); |
|
|
|
pilot.y = channel_right->get_control_in() / float(RC_SCALE) * g.max_pos_xy * blimp.scheduler.get_loop_period_s(); |
|
|
|
|
|
|
|
pilot.z = channel_down->get_control_in() / float(RC_SCALE) * g.max_pos_z * blimp.scheduler.get_loop_period_s(); |
|
|
|
float pilot_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_pos_yaw * blimp.scheduler.get_loop_period_s(); |
|
|
|
float pilot_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_pos_yaw * blimp.scheduler.get_loop_period_s(); |
|
|
|
|
|
|
|
|
|
|
|
if (g.simple_mode == 0){ |
|
|
|
if (g.simple_mode == 0){ |
|
|
|
//If simple mode is disabled, input is in body-frame, thus needs to be rotated.
|
|
|
|
//If simple mode is disabled, input is in body-frame, thus needs to be rotated.
|
|
|
|
blimp.rotate_BF_to_NE(pilot_fwd, pilot_rgt); |
|
|
|
blimp.rotate_BF_to_NE(pilot.xy()); |
|
|
|
} |
|
|
|
} |
|
|
|
target_pos.x += pilot_fwd; |
|
|
|
target_pos.x += pilot.x; |
|
|
|
target_pos.y += pilot_rgt; |
|
|
|
target_pos.y += pilot.y; |
|
|
|
target_pos.z += pilot_dwn; |
|
|
|
target_pos.z += pilot.z; |
|
|
|
target_yaw = wrap_PI(target_yaw + pilot_yaw); |
|
|
|
target_yaw = wrap_PI(target_yaw + pilot_yaw); |
|
|
|
|
|
|
|
|
|
|
|
//Pos controller's output becomes target for velocity controller
|
|
|
|
//Pos controller's output becomes target for velocity controller
|
|
|
@ -38,21 +39,24 @@ void ModeLoiter::run() |
|
|
|
|
|
|
|
|
|
|
|
Vector3f target_vel_ef_c{constrain_float(target_vel_ef.x, -g.max_vel_xy, g.max_vel_xy), |
|
|
|
Vector3f target_vel_ef_c{constrain_float(target_vel_ef.x, -g.max_vel_xy, g.max_vel_xy), |
|
|
|
constrain_float(target_vel_ef.y, -g.max_vel_xy, g.max_vel_xy), |
|
|
|
constrain_float(target_vel_ef.y, -g.max_vel_xy, g.max_vel_xy), |
|
|
|
constrain_float(target_vel_ef.z, -g.max_vel_xy, g.max_vel_xy)}; |
|
|
|
constrain_float(target_vel_ef.z, -g.max_vel_z, g.max_vel_z)}; |
|
|
|
float target_vel_yaw_c = constrain_float(target_vel_yaw, -g.max_vel_yaw, g.max_vel_yaw); |
|
|
|
float target_vel_yaw_c = constrain_float(target_vel_yaw, -g.max_vel_yaw, g.max_vel_yaw); |
|
|
|
|
|
|
|
|
|
|
|
Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c, blimp.vel_ned_filtd, {0,0,0}); |
|
|
|
Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c, blimp.vel_ned_filtd, {0,0,0}); |
|
|
|
float act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z, blimp.vel_ned_filtd.z); |
|
|
|
float act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z, blimp.vel_ned_filtd.z); |
|
|
|
blimp.rotate_NE_to_BF(actuator.x, actuator.y); |
|
|
|
blimp.rotate_NE_to_BF(actuator); |
|
|
|
float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c, blimp.vel_yaw_filtd); |
|
|
|
float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c, blimp.vel_yaw_filtd); |
|
|
|
|
|
|
|
|
|
|
|
if(!(blimp.g.dis_mask & (1<<(2-1)))){ |
|
|
|
if(!(blimp.g.dis_mask & (1<<(2-1)))){ |
|
|
|
motors->front_out = actuator.x; |
|
|
|
motors->front_out = actuator.x; |
|
|
|
} if(!(blimp.g.dis_mask & (1<<(1-1)))){ |
|
|
|
} |
|
|
|
|
|
|
|
if(!(blimp.g.dis_mask & (1<<(1-1)))){ |
|
|
|
motors->right_out = actuator.y; |
|
|
|
motors->right_out = actuator.y; |
|
|
|
} if(!(blimp.g.dis_mask & (1<<(3-1)))){ |
|
|
|
} |
|
|
|
|
|
|
|
if(!(blimp.g.dis_mask & (1<<(3-1)))){ |
|
|
|
motors->down_out = act_down; |
|
|
|
motors->down_out = act_down; |
|
|
|
} if(!(blimp.g.dis_mask & (1<<(4-1)))){ |
|
|
|
} |
|
|
|
|
|
|
|
if(!(blimp.g.dis_mask & (1<<(4-1)))){ |
|
|
|
motors->yaw_out = act_yaw; |
|
|
|
motors->yaw_out = act_yaw; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|