#include "Sub.h" //#include "/AP_Math/AP_Math.h" 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 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 { // If we don't have a mavlink attitude target, we use the pilot's input instead //get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); //get_pilot_desired_lean_angles((int16_t)(channel_lateral->norm_input()*5700), (int16_t)((0.5-channel_throttle->norm_input())*5700*2), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); //get_pilot_desired_lean_angles(0, (int16_t)((0.5-channel_throttle->norm_input())*5700*2), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); get_pilot_desired_lean_angles(0, (int16_t)((0.5-channel_throttle->norm_input())*5700), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max()); target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()*0.3);//*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; ahrs.get_quat_body_to_ned(attitude_desired_quat_); last_input_ms = tnow; attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); } 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_); } } } // 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(); //handle_attitude(); pos_control.update_z_controller(); // 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, motors.get_throttle_in_bidirectional()); // Output the Z controller + pilot input to all motors. //TODO: scale throttle with the ammount of thrusters in the given direction // motors.set_throttle(0.5+throttle_vehicle_frame.z + channel_throttle->norm_input()-0.5); // motors.set_throttle(throttle_vehicle_frame.z + 1.0-(float)PressLevel_f*0.1); motors.set_throttle(throttle_vehicle_frame.z + gaindelay(1.0-(float)PressLevel_f*0.1,updowmgain)); rov_message.pressure_level = int(PressLevel); motors.set_forward(constrain_float(-throttle_vehicle_frame.x + getgainf(channel_forward->norm_input()),-0.8,0.8));//*0.6 变慢 motors.set_lateral(constrain_float(-throttle_vehicle_frame.y + getgainf(channel_lateral->norm_input()),-0.8,0.8));//*0.6 变慢 // We rotate the RC inputs to the earth frame to check if the user is giving an input that would change the depth. //Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), channel_lateral->norm_input(), (2.0f*(-0.5f+channel_throttle->norm_input()))); //Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), channel_lateral->norm_input(), (2.0*(0.5-PressLevel_f*0.1))); Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), 0.0, (2.0*(0.5-PressLevel_f*0.1)));//去掉侧移影响 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(); //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 +20);//cm holding_depth = true; } else if (!holding_depth) { //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);//cm 当前深度 holding_depth = true; } } } /* float rmpforward(float _gain){ static uint16_t rmpcounter = 0; float get_forward_gain = motors.get_forward(); float temp=0; rmpcounter++; if (rmpcounter>20) { rmpcounter =0; if(get_forward_gain - _gain>0.01){ temp = get_forward_gain-0.01; }else if(get_forward_gain- _gain<-0.01){ temp = get_forward_gain+0.01; } else{ temp = _gain; } } if (_gain>0.3) { temp =constrain_float(temp,0.4,1.0); }else if(temp<-0.3){ temp = constrain_float(temp,-1.0,-0.4); }else{ temp=0.0; } }*/