mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1351 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
669e276da6
commit
a446389c8e
@ -31,6 +31,7 @@ Command ID Name Parameter 1 Altitude Latitude Longitude
|
||||
0x16 CMD_TAKEOFF angle altitude - -
|
||||
0x17 CMD_ALTITUDE - altitude - -
|
||||
0x18 CMD_R_WAYPOINT - altitude rlat rlon
|
||||
0x19 CMD_TARGET - altitude lat lon
|
||||
|
||||
|
||||
***********************************
|
||||
|
@ -206,10 +206,13 @@ void process_may()
|
||||
break;
|
||||
|
||||
case CMD_ANGLE:
|
||||
// p1: bearing
|
||||
// alt: speed
|
||||
// lat: direction (-1,1),
|
||||
// lng: rel (1) abs (0)
|
||||
|
||||
// target angle in degrees
|
||||
command_yaw_start = nav_yaw; // current position
|
||||
command_yaw_end = next_command.p1 * 100;
|
||||
|
||||
command_yaw_start = nav_yaw; // current position
|
||||
command_yaw_start_time = millis();
|
||||
|
||||
// which direction to turn
|
||||
@ -222,8 +225,12 @@ void process_may()
|
||||
command_yaw_dir = (command_yaw_end > 0) ? 1 : -1;
|
||||
command_yaw_end += nav_yaw;
|
||||
command_yaw_end = wrap_360(command_yaw_end);
|
||||
} else {
|
||||
// absolute
|
||||
command_yaw_end = next_command.p1 * 100;
|
||||
}
|
||||
|
||||
|
||||
// if unspecified go 10° a second
|
||||
if(command_yaw_speed == 0)
|
||||
command_yaw_speed = 10;
|
||||
@ -251,6 +258,8 @@ void process_may()
|
||||
// rate to turn deg per second - default is ten
|
||||
command_yaw_speed = next_command.alt;
|
||||
command_yaw_time = command_yaw_delta / command_yaw_speed;
|
||||
//9000 turn in 10 seconds
|
||||
//command_yaw_time = 9000/ 10 = 900° per second
|
||||
|
||||
break;
|
||||
|
||||
@ -431,17 +440,18 @@ void verify_must()
|
||||
break;
|
||||
|
||||
case CMD_LOITER: // Just plain LOITER
|
||||
break;
|
||||
break;
|
||||
|
||||
case CMD_ANGLE:
|
||||
if((millis() - command_yaw_start_time) > command_yaw_time){
|
||||
command_must_index = 0;
|
||||
nav_yaw = command_yaw_end;
|
||||
}else{
|
||||
// else we need to be at a certain place
|
||||
// power is a ratio of the time : .5 = half done
|
||||
power = (float)(millis() - command_yaw_start_time) / (float)command_yaw_time;
|
||||
nav_yaw = command_yaw_start + ((float)command_yaw_delta * power * command_yaw_dir);
|
||||
}
|
||||
|
||||
// else we need to be at a certain place
|
||||
power = (float)(millis() - command_yaw_start_time) / (float)command_yaw_time;
|
||||
nav_yaw = command_yaw_start + ((float)command_yaw_delta * power * command_yaw_dir);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -123,9 +123,10 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
rc_3.calc_pwm();
|
||||
rc_4.calc_pwm();
|
||||
|
||||
//Serial.printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\n"), (rc_1.control_in), (rc_2.control_in), (rc_3.control_in), (rc_4.control_in), rc_5.control_in, rc_6.control_in, rc_7.control_in);
|
||||
Serial.printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\n"), (rc_1.control_in), (rc_2.control_in), (rc_3.control_in), (rc_4.control_in), rc_5.control_in, rc_6.control_in, rc_7.control_in);
|
||||
//Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d\n"), (rc_1.servo_out / 100), (rc_2.servo_out / 100), rc_3.servo_out, (rc_4.servo_out / 100));
|
||||
Serial.printf_P(PSTR( "min: %d"
|
||||
|
||||
/*Serial.printf_P(PSTR( "min: %d"
|
||||
"\t in: %d"
|
||||
"\t pwm_in: %d"
|
||||
"\t sout: %d"
|
||||
@ -136,7 +137,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
rc_3.servo_out,
|
||||
rc_3.pwm_out
|
||||
);
|
||||
|
||||
*/
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user