#include "Sub.h" extern mavlink_rov_state_monitoring_t rov_message; // stabilize_init - initialise stabilize controller bool Sub::sport_init() { // set target altitude to zero for reporting pos_control.set_alt_target(0); if (prev_control_mode == ALT_HOLD) { last_roll = ahrs.roll_sensor; last_pitch = ahrs.pitch_sensor; } else { last_roll = 0; last_pitch = 0; } last_yaw = ahrs.yaw_sensor; pitch_input_inc=0; yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位 last_input_ms = AP_HAL::millis(); return true; } // stabilize_run - runs the main stabilize controller // should be called at 100hz or more void Sub::sport_run() { // if not armed set throttle to zero and exit immediately if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); attitude_control.set_throttle_out(0,true,g.throttle_filt); attitude_control.relax_attitude_controllers(); last_roll = 0; last_pitch = 0; last_yaw = ahrs.yaw_sensor; yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位 return; } motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); 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()); target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); 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); } 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; 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); } } // handle_attitude(); // output pilot's throttle //attitude_control.set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt); attitude_control.set_throttle_out(1.0-(float)PressLevel_f*0.1, false, g.throttle_filt);//压力分级 rov_message.pressure_level = int(PressLevel); //control_in is range -1000-1000 //radio_in is raw pwm value motors.set_forward(channel_forward->norm_input()); //motors.set_lateral(channel_lateral->norm_input()); motors.set_lateral(0); static int j = 0; j++; if(j>800) { //gcs().send_text(MAV_SEVERITY_INFO, " roll p y %d %d %d\n",(int16_t)(channel_lateral->norm_input()*5700),(int16_t)((0.5-channel_throttle->norm_input())*5700*2),channel_yaw->get_control_in()); //gcs().send_text(MAV_SEVERITY_INFO, " throttle forward lateral %f %f %f \n",(float)PressLevel_f*0.1,channel_forward->norm_input()); //gcs().send_text(MAV_SEVERITY_INFO, " channel_roll p y %d %d %d\n",channel_roll->get_control_in(),channel_pitch->get_control_in(),channel_yaw->get_control_in()); //gcs().send_text(MAV_SEVERITY_INFO, " throttle forward lateral %f %f %f \n",channel_throttle->norm_input(),channel_forward->norm_input(),channel_lateral->norm_input()); j=0; } }