123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431 |
- #include "Sub.h"
- //#include "/AP_Math/AP_Math.h"
- #define PI 3.141592653589793238462643383279502884
- extern mavlink_rov_state_monitoring_t rov_message;
- Quaternion attitude_desired_quat_;
- /*
- * control_althold.pde - init and run calls for althold, flight mode
- */
- // althold_init - initialise althold controller
- bool Sub::sport_init()
- {
- attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
- //holding_depth = false;
- //检查是否有深度计存在
- if(!control_check_barometer()) {
- return false;
- }
- // initialize vertical speeds and leash lengths
- // sets the maximum speed up and down returned by position controller
- //get_pilot_speed_dn QGC PILOT 设置的值
- pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);//(-500,500)设置最大最小速度 和刹车长度
- pos_control.set_max_accel_z(g.pilot_accel_z);//设置最大加速度值 和刹车长度
- pos_control.relax_alt_hold_controllers();//目标高度为当前高度,目标速度和上次速度 当前速度
- //
- //pos_control.set_target_to_stopping_point_z();//刹车长度 根据当前速度估计目标深度
- pos_control.calc_leash_length_z();//刹车长度 12.19
- pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度12.19
- holding_depth = true;
- //ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19 使用roll pitch =0的姿态
-
- attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);
- last_roll = 0;
- last_pitch = 0;
-
- updowmgain =0.5;
- last_yaw = ahrs.yaw_sensor;
- last_input_ms = AP_HAL::millis();
- last_input_ms_stable = AP_HAL::millis();
-
-
-
- return true;
- }
- void Sub::handle_attitude_sport(){
- uint32_t tnow = AP_HAL::millis();
- // get pilot desired lean angles
- float target_roll, target_pitch, target_yaw;
- // Check if set_attitude_target_no_gps is valid
- if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
- Quaternion(
- set_attitude_target_no_gps.packet.q
- ).to_euler(
- target_roll,
- target_pitch,
- target_yaw
- );
- target_roll = 100 * degrees(target_roll);
- target_pitch = 100 * degrees(target_pitch);
- target_yaw = 100 * degrees(target_yaw);
- last_roll = target_roll;
- last_pitch = target_pitch;
- last_yaw = target_yaw;
-
- attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
- } else {
- float throttle = 2*(0.5-channel_throttle->norm_input());
- float yaw = channel_yaw->norm_input();
- if (fabsf(throttle)>=fabsf(yaw))
- {
- yaw = 0.0;
- }else{
- throttle = 0.0;
- yaw = channel_yaw->get_control_in()*0.3;
- }
- get_pilot_desired_lean_angles(0, (int16_t)(throttle/2.0*5700), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
- target_yaw = get_pilot_desired_yaw_rate(yaw);//*0.6 变慢
-
- if (abs(target_roll) > 300 || abs(target_pitch) > 300) {
- //last_roll = ahrs.roll_sensor;
- //last_pitch = ahrs.pitch_sensor;
- //last_yaw = ahrs.yaw_sensor;
-
- last_input_ms = tnow;
- attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
- ahrs.get_quat_body_to_ned(attitude_desired_quat_);
- } else if (abs(target_yaw) > 300) {
- // if only yaw is being controlled, don't update pitch and roll
- attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
- //last_yaw = ahrs.yaw_sensor;
- ahrs.get_quat_body_to_ned(attitude_desired_quat_);
- last_input_ms = tnow;
- } else if (tnow < last_input_ms + 250) {
- // just brake for a few mooments so we don't bounce
- last_yaw = ahrs.yaw_sensor;
- attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
- } else {
- // Lock attitude
- //attitude_control.input_euler_angle_roll_pitch_yaw(last_roll, last_pitch, last_yaw, true);
- attitude_control.input_quaternion(attitude_desired_quat_);
- }
- }
- }
- void Sub::sport_run_alt(void){
-
-
- // When unarmed, disable motors and stabilization
- if (!motors.armed()) {
-
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
- // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
- attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- pos_control.relax_alt_hold_controllers();
- pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
-
- updowmgain =0.5;
- last_roll = 0;
- last_pitch = 0;
- last_yaw = ahrs.yaw_sensor;
- holding_depth = false;
- // ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19
- attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);
-
- return;
- }
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
- handle_attitude_sport();
- //pos_control.update_z_controller();//输出了set_throttle_out
- Matrix3f mat_body = ahrs.get_rotation_body_to_ned();
- //Vector3f Zb = mat_body*Vector3f(0,0,1);
- //Vector3f Ze = Vector3f(0,0,1);
- //float thetaz = Zb*Ze;//计算有没有翻过来
- Matrix3f mat_half;
- float beta = 0.0;
- float dot=0.0;
- if(mat_body.c.x<0.98 && mat_body.c.x>-0.98){//大约78.5度认为Z轴指向方向,小于78.5进入X轴指向方向
- Vector3f Xbx = mat_body*Vector3f(1,0,0);
- Xbx.z = 0.0;
- Vector3f Xex = Vector3f(1,0,0);
- dot = Xbx * Xex/Xbx.length();
- beta = acosf(dot );
- if (Xbx.y<0)
- {
- beta = -beta;
- }
- Vector3f Xbz = mat_body*Vector3f(0,0,1);
- Vector3f Xez = Vector3f(0,0,1);
- float dotz = Xbz * Xez/Xbz.length();
- if (dotz<0)
- {
- beta = beta-PI;
- if (beta<-PI)
- {
- beta = beta+2*PI;
- }
- }
-
- mat_half.a.x= cosf(beta);
- mat_half.a.y=-sinf(beta);
- mat_half.a.z=0.0;
- mat_half.b.x= sinf(beta);
- mat_half.b.y= cosf(beta);
- mat_half.b.z=0.0;
- mat_half.c.x= 0.0;
- mat_half.c.y= 0.0;
- mat_half.c.z=1.0;
- }
- else{
-
- Vector3f Xbz = mat_body*Vector3f(0,0,1);
- Xbz.z = 0.0;
- Vector3f Xex = Vector3f(1,0,0);
- dot = Xbz * Xex/Xbz.length();
- beta = acosf(dot );
- if (Xbz.y<0)
- {
- beta = -beta;
- }
- if (mat_body.c.x>0)//头朝下
- {
- beta = beta-PI;
- if (beta<-PI)
- {
- beta = beta+2*PI;
- }
- }
- mat_half.a.x= cosf(beta);
- mat_half.a.y=-sinf(beta);
- mat_half.a.z=0.0;
- mat_half.b.x= sinf(beta);
- mat_half.b.y= cosf(beta);
- mat_half.b.z=0.0;
- mat_half.c.x= 0.0;
- mat_half.c.y= 0.0;
- mat_half.c.z=1.0;
- }
- // mat 地到half状态
- Matrix3f rc_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed()*mat_half;//rc_vehicle_frame(half)到body
-
-
- float forward = channel_forward->norm_input();
- float lateral =channel_lateral->norm_input();
- if (fabsf(forward)>=fabsf(lateral))
- {
- lateral = 0.0;
- }else{
- forward = 0.0;
- }
-
- Vector3f rc_throttle_forward = Vector3f(getgainf(forward),0, 0);//手柄的值
- Vector3f rc_throttle_lateral = Vector3f(0, getgainf(lateral), 0);//手柄的值
- Vector3f rc_throttle = Vector3f(0, 0, 2*(gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)-0.5));//手柄的值
-
-
- Vector3f rc_throttle_vehicle_frame1 = rc_vehicle_frame*rc_throttle_forward;//手柄从half系到body系
- Vector3f rc_throttle_vehicle_frame2 = rc_vehicle_frame*rc_throttle_lateral;//手柄从half系到body系
- Vector3f rc_throttle_vehicle_frame3 = rc_vehicle_frame*rc_throttle;//手柄从half系到body系
-
- Vector3f rc_throttle_vehicle_frame;
- rc_throttle_vehicle_frame.x = rc_throttle_vehicle_frame1.x + rc_throttle_vehicle_frame2.x - rc_throttle_vehicle_frame3.x;
- rc_throttle_vehicle_frame.y = rc_throttle_vehicle_frame1.y + rc_throttle_vehicle_frame2.y - rc_throttle_vehicle_frame3.y;
- rc_throttle_vehicle_frame.z = -rc_throttle_vehicle_frame1.z - rc_throttle_vehicle_frame2.z + rc_throttle_vehicle_frame3.z;
- // Read the output of the z controller and rotate it so it always points up
- //将Z轴输出变到机体坐标系
- //Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, motors.get_throttle_in_bidirectional());
- float z_throttle = pos_control.update_z_controller_f();//输出了set_throttle_out
- Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, z_throttle);
-
-
- //手柄控制和Z轴输出的叠加
- motors.set_forward(-throttle_vehicle_frame.x +rc_throttle_vehicle_frame.x);
- motors.set_lateral(-throttle_vehicle_frame.y +rc_throttle_vehicle_frame.y);//*0.6 变慢
- motors.set_throttle(throttle_vehicle_frame.z +rc_throttle_vehicle_frame.z/2+0.5);
- rov_message.pressure_level = int(PressLevel);
-
- Vector3f earth_frame_rc_inputs = Vector3f(0.0, 0.0, 2*(gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)-0.5));//去掉侧移影响
-
- if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
- // reset z targets to current values
- holding_depth = false;
- pos_control.relax_alt_hold_controllers();
-
-
-
- } else { // hold z
- if (ap.at_surface) { //最大油门不能向上动
- pos_control.set_alt_target(g.surface_depth - 10.0f); // set target to 5cm below surface level
- holding_depth = true;
-
-
- } else if (ap.at_bottom) {//最大油门不能向下动
- //pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
- pos_control.set_alt_target(barometer.get_altitude()*100 +10);//cm
- holding_depth = true;
-
-
- } else if (!holding_depth) {
-
- pos_control.calc_leash_length_z();//刹车长度 12.19
- // pos_control.set_target_to_stopping_point_z();//有对位置的付值
- pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
-
- holding_depth = true;
-
- }
- }
- static bool lastdepth = holding_depth;
- if(lastdepth !=holding_depth){
- lastdepth = holding_depth;
-
-
- gcs().send_text(MAV_SEVERITY_INFO, "get_alt_target %d %f %f\n",(int)holding_depth,pos_control.get_alt_target(),barometer.get_altitude()*100);
-
- }
- static uint16_t count = 0;
- count++;
- if (count>300)
- {
- count = 0;
-
- gcs().send_text(MAV_SEVERITY_INFO, "alt %f %f %f %f\n",pos_control.get_alt_target(),barometer.get_altitude()*100,pos_control.alt_rate.get(),motors.get_throttle());
- gcs().send_text(MAV_SEVERITY_INFO, "surf %d %d %f \n",(int)ap.at_surface,(int)ap.at_bottom,motors.get_throttle_thrust_max());
- }
- }
- void Sub::altcontrol(){
- float z_throttle = pos_control.update_z_controller_f();//输出了set_throttle_out
- // Read the output of the z controller and rotate it so it always points up
- //变到机体坐标系
- Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, z_throttle);
- // Output the Z controller + pilot input to all motors.
- motors.set_throttle(throttle_vehicle_frame.z + gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain));
-
- static uint16_t j=0;
- j++;
- if(j>300)
- {
- gcs().send_text(MAV_SEVERITY_INFO, " sportthrottle %f %f %f \n",z_throttle,throttle_vehicle_frame.z,motors.get_throttle());
- j=0;
- }
- rov_message.pressure_level = int(PressLevel);
- float forward = channel_forward->norm_input();
- float lateral =channel_lateral->norm_input();
- if (fabsf(forward)>=fabsf(lateral))
- {
- lateral = 0.0;
- }else{
- forward = 0.0;
- }
- motors.set_forward(constrain_float(-throttle_vehicle_frame.x + getgainf(forward),-0.8,0.8));//*0.6 变慢
- motors.set_lateral(constrain_float(-throttle_vehicle_frame.y + getgainf(lateral),-0.8,0.8));//*0.6 变慢
-
- Vector3f earth_frame_rc_inputs1 = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), 0.0, 2*(gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)-0.5));//去掉侧移影响
-
-
- if (fabsf(earth_frame_rc_inputs1.z) > 0.05f) { // Throttle input above 5%
- // reset z targets to current values
- holding_depth = false;
- pos_control.relax_alt_hold_controllers();
-
- //pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
-
- } else { // hold z
- if (ap.at_surface) { //最大油门不能向上动
- pos_control.set_alt_target(g.surface_depth - 10.0f); // set target to 5cm below surface level
- holding_depth = true;
- } else if (ap.at_bottom) {//最大油门不能向下动
- //pos_control.set_alt_target(inertial_nav.get_altitude() + 20.0f); // set target to 10 cm above bottom
- pos_control.set_alt_target(barometer.get_altitude()*100+10);//cm
- holding_depth = true;
-
- } else if (!holding_depth) {
- pos_control.calc_leash_length_z();//刹车长度 12.19
- pos_control.set_alt_target(barometer.get_altitude()*100);//cm 当前深度
- holding_depth = true;
- }
- }
- static bool lastdepth = holding_depth;
- if(lastdepth !=holding_depth){
- lastdepth = holding_depth;
- gcs().send_text(MAV_SEVERITY_INFO, " get_alt_target %d %f \n",(int)holding_depth,motors.get_throttle());
- }
-
- static uint16_t count = 0;
- count++;
- if (count>300)
- {
- count = 0;
- gcs().send_text(MAV_SEVERITY_INFO, " surface %d %d %d\n",(int)ap.at_surface,(int)ap.at_bottom,(int)motors.limit.throttle_lower);
- gcs().send_text(MAV_SEVERITY_INFO, " altitude %f %f \n",pos_control.get_alt_target(),barometer.get_altitude()*100);
-
- }
- }
- // althold_run - runs the althold controller
- // should be called at 100hz or more
- void Sub::sport_run()
- {
-
- // When unarmed, disable motors and stabilization
- if (!motors.armed()) {
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
- // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
- attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- pos_control.relax_alt_hold_controllers();
-
- //pos_control.set_alt_target(barometer.get_altitude()*100);//当前深度
- updowmgain =0.5;
- last_roll = 0;
- last_pitch = 0;
- last_yaw = ahrs.yaw_sensor;
- holding_depth = false;
- ahrs.get_quat_body_to_ned(attitude_desired_quat_);//12.19
-
- return;
- }
- // Vehicle is armed, motors are free to run
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
-
- handle_attitude_sport();
- altcontrol();
-
- }
|