#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_; //Matrix3f last_desired; /* * 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.reset_I(); //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);//初始化 rotpitch.identity(); attitude_desired_quat_.rotation_matrix(rotyaw); last_roll = 0; last_pitch = 0; updowmgain =0.5; delaygain = 401; continuous_count=0; continuous_countdec=0; last_continuous = 0; last_yaw = ahrs.yaw_sensor; last_input_ms = AP_HAL::millis(); last_input_ms_stable = AP_HAL::millis(); //updown_gain = 0.0; 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.35; } get_pilot_desired_lean_angles(0, (int16_t)(throttle/1.5*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_pitch) > 300) { last_input_ms = tnow; attitude_control.input_rate_bf_roll_pitch_yaw(0, target_pitch, 0); //ahrs.get_quat_body_to_ned(attitude_desired_quat_); Matrix3f mat_body = ahrs.get_rotation_body_to_ned();//03.17 float pitch_ang = get_pitch_to_ned(mat_body); rotpitch.from_euler(0,pitch_ang,0);//pitch 旋转矩阵 } 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); Matrix3f mat_body = ahrs.get_rotation_body_to_ned();//03.17 get_heading_to_ned(rotyaw,mat_body);//yaw旋转矩阵 //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 Matrix3f mat_body = ahrs.get_rotation_body_to_ned();//03.17 get_heading_to_ned(rotyaw,mat_body);//yaw旋转矩阵 attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0); } else { // Lock attitude float depth = barometer.get_altitude()*100; // cm if(fabsf(depth)<50){//水面附近 float maxsinpitch = constrain_float(fabsf(depth)/50.0,0.0,1.0);//40深度传感器到体长+10 余量 可以允许的最大pitch角的绝对值 float nowsinpitch = rotpitch.a.z;//当前的pitch角 Matrix3f rotpitch_limit; if (fabsf(nowsinpitch)>maxsinpitch)//说明比允许的大 姿态应该是恢复水平一些 { float pitch_ang = get_pitch_to_ned(rotpitch);//目前的pith if (fabsf(pitch_ang)400) { count = 0; // gcs().send_text(MAV_SEVERITY_INFO, "ahr %f %f %f \n",nowsinpitch,maxsinpitch,get_pitch_to_ned(rotpitch_limit)); } }else{ attitude_desired_quat_.from_rotation_matrix(rotyaw*rotpitch); } attitude_control.input_quaternion(attitude_desired_quat_); //attitude_desired_quat_.from_rotation_matrix(rotyaw*rotpitch); //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.reset_I(); 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; rotpitch.identity(); attitude_desired_quat_.from_euler(0.0, 0.0,ahrs.yaw);//初始化 attitude_desired_quat_.rotation_matrix(rotyaw); delaygain = 401; continuous_count=0; continuous_countdec=0; last_continuous = 0; 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(); Matrix3f mat_half; get_heading_to_ned(mat_half,mat_body);//得到half状态 // 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; } //手柄转到机体系------------------------ float joystick_z = 2*(gaindelay(1.0-(float)PressLevel_f*0.1)-0.5);//-1~1 Vector3f rc_throttle_forward = Vector3f(getgainf(forward),0, 0);//手柄的值 Vector3f rc_throttle_lateral = Vector3f(0, getgainf(lateral), 0);//手柄的值 Vector3f rc_throttle = Vector3f(0, 0, joystick_z);//手柄的值 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 //深度保持控制 float z_throttle = pos_control.update_z_controller_f();//输出了垂直变化量 //将深度保持控制的对地系转到机体系 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); 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, joystick_z);//仅仅与竖直有关 手柄是在half系 Z轴 bottom_detectorgain(); 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(surface_depth_use()*100 - 10.0f); // set target to 5cm below surface level holding_depth = true; } else if (ap.at_bottom||bottom_set) {//最大油门不能向下动 //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 %d %f %f\n",(int)holding_depth,pos_control.get_alt_target(),barometer.get_altitude()*100); } static uint16_t count = 0; count++; if (count>400) { count = 0; // gcs().send_text(MAV_SEVERITY_INFO, "surf %d %d %d %f\n",(int)ap.at_surface,(int)ap.at_bottom,(int)motors.limit.throttle_upper,(float)motors.get_throttle()); // 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(),joystick_z); } } void Sub::altcontrol(){//相对机体系的手柄控制 //深度控制 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); // Output the Z controller + pilot input to all motors. float z_throttle_joystic = gaindelay(1.0-(float)PressLevel_f*0.1);//0~1 motors.set_throttle(throttle_vehicle_frame.z + z_throttle_joystic);//Z轴油门 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, (z_throttle_joystic-0.5)*2);//去掉侧移影响 bottom_detectorgain(); 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(); } else { // hold z if (ap.at_surface) { //最大油门不能向上动 pos_control.set_alt_target(surface_depth_use()*100 - 10.0f); // set target to 5cm below surface level holding_depth = true; } else if (ap.at_bottom||bottom_set) {//最大油门不能向下动 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_upper); gcs().send_text(MAV_SEVERITY_INFO, " altitude %f %f %f\n",pos_control.get_alt_target(),barometer.get_altitude()*100,motors.get_throttle()); } }