diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index e9847c2a4d..8cd97efead 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1201,15 +1201,26 @@ void Copter::convert_pid_parameters(void) { // conversion info const AP_Param::ConversionInfo pid_conversion_info[] = { - { Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" }, - { Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" }, - { Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" }, - { Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_RAT_PIT_P" }, - { Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_RAT_PIT_I" }, - { Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_RAT_PIT_D" }, - { Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_RAT_YAW_P" }, - { Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" }, - { Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" }, + // { Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" }, + // { Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" }, + // { Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" }, + // { Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_RAT_PIT_P" }, + // { Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_RAT_PIT_I" }, + // { Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_RAT_PIT_D" }, + // { Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_RAT_YAW_P" }, + // { Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" }, + // { Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" }, + + { Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_AA_RLL_P" }, + { Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_AA_RLL_I" }, + { Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_AA_RLL_D" }, + { Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_AA_PIT_P" }, + { Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_AA_PIT_I" }, + { Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_AA_PIT_D" }, + { Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_AA_YAW_P" }, + { Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_AA_YAW_I" }, + { Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_AA_YAW_D" }, + #if FRAME_CONFIG == HELI_FRAME { Parameters::k_param_pid_rate_roll, 4, AP_PARAM_FLOAT, "ATC_RAT_RLL_VFF" }, { Parameters::k_param_pid_rate_pitch, 4, AP_PARAM_FLOAT, "ATC_RAT_PIT_VFF" }, diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 120975848b..b99888d0cb 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -1069,9 +1069,12 @@ bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix, const char *pid_name; AC_PID &pid; } pids[] = { - { "RAT_RLL", get_rate_roll_pid() }, - { "RAT_PIT", get_rate_pitch_pid() }, - { "RAT_YAW", get_rate_yaw_pid() }, + // { "RAT_RLL", get_rate_roll_pid() }, + // { "RAT_PIT", get_rate_pitch_pid() }, + // { "RAT_YAW", get_rate_yaw_pid() }, + { "AA_RLL", get_rate_roll_pid() }, + { "AA_PIT", get_rate_pitch_pid() }, + { "AA_YAW", get_rate_yaw_pid() }, }; for (uint8_t i=0; i ./log/sitl.log 2>&1 & diff --git a/show_tcp_sitl.sh b/show_tcp_sitl.sh new file mode 100755 index 0000000000..a63ee0e0fd --- /dev/null +++ b/show_tcp_sitl.sh @@ -0,0 +1 @@ +ps -aux|grep sitl diff --git a/sitl.sh b/sitl.sh index 1fa3e8c125..f96e721784 100755 --- a/sitl.sh +++ b/sitl.sh @@ -1 +1 @@ - ./Tools/autotest/sim_vehicle.py -j4 -L CYDS --console --out 192.168.10.137:14552 --map -A --serial5=uart:/dev/ttyS1:115200 -v ArduCopter \ No newline at end of file + ./Tools/autotest/sim_vehicle.py -j4 -L CYDS --console --out 192.168.0.51:14552 --map -A "--serial5=uart:/dev/pts/1:230400" -v ArduCopter \ No newline at end of file diff --git a/tcp_sitl.sh b/tcp_sitl.sh new file mode 100755 index 0000000000..2b690d4e19 --- /dev/null +++ b/tcp_sitl.sh @@ -0,0 +1 @@ +./Tools/autotest/sim_vehicle.py -j4 -L CYDS --console --out 192.168.0.51:14552 --no-mavproxy ArduCopter -A "--serial5=uart:/dev/pts/1:230400" -v ArduCopter