mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Copter: remove old comments
This commit is contained in:
parent
e5535e35b3
commit
284aa2217f
@ -993,7 +993,6 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
send_message(MSG_RAW_IMU1);
|
||||
send_message(MSG_RAW_IMU2);
|
||||
send_message(MSG_RAW_IMU3);
|
||||
//cliSerial->printf("mav1 %d\n", (int)streamRateRawSensors.get());
|
||||
}
|
||||
|
||||
if (gcs_out_of_time) return;
|
||||
@ -1017,7 +1016,6 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
|
||||
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
||||
send_message(MSG_SERVO_OUT);
|
||||
//cliSerial->printf("mav4 %d\n", (int)streamRateRawController.get());
|
||||
}
|
||||
|
||||
if (gcs_out_of_time) return;
|
||||
@ -1025,7 +1023,6 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
||||
send_message(MSG_RADIO_OUT);
|
||||
send_message(MSG_RADIO_IN);
|
||||
//cliSerial->printf("mav5 %d\n", (int)streamRateRCChannels.get());
|
||||
}
|
||||
|
||||
if (gcs_out_of_time) return;
|
||||
@ -1033,14 +1030,12 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
if (stream_trigger(STREAM_EXTRA1)) {
|
||||
send_message(MSG_ATTITUDE);
|
||||
send_message(MSG_SIMSTATE);
|
||||
//cliSerial->printf("mav6 %d\n", (int)streamRateExtra1.get());
|
||||
}
|
||||
|
||||
if (gcs_out_of_time) return;
|
||||
|
||||
if (stream_trigger(STREAM_EXTRA2)) {
|
||||
send_message(MSG_VFR_HUD);
|
||||
//cliSerial->printf("mav7 %d\n", (int)streamRateExtra2.get());
|
||||
}
|
||||
|
||||
if (gcs_out_of_time) return;
|
||||
|
@ -69,7 +69,6 @@ static void set_cmd_with_index(struct Location temp, int i)
|
||||
{
|
||||
|
||||
i = constrain_int16(i, 0, g.command_total.get());
|
||||
//cliSerial->printf("set_command: %d with id: %d\n", i, temp.id);
|
||||
|
||||
// store home as 0 altitude!!!
|
||||
// Home is always a MAV_CMD_NAV_WAYPOINT (16)
|
||||
|
@ -797,7 +797,6 @@ static bool verify_change_alt()
|
||||
|
||||
static bool verify_within_distance()
|
||||
{
|
||||
//cliSerial->printf("cond dist :%d\n", (int)condition_value);
|
||||
if (wp_distance < max(condition_value,0)) {
|
||||
condition_value = 0;
|
||||
return true;
|
||||
@ -864,27 +863,20 @@ static void do_jump()
|
||||
// when in use, it contains the current remaining jumps
|
||||
static int8_t jump = -10; // used to track loops in jump command
|
||||
|
||||
//cliSerial->printf("do Jump: %d\n", jump);
|
||||
|
||||
if(jump == -10) {
|
||||
//cliSerial->printf("Fresh Jump\n");
|
||||
// we use a locally stored index for jump
|
||||
jump = command_cond_queue.lat;
|
||||
}
|
||||
//cliSerial->printf("Jumps left: %d\n",jump);
|
||||
|
||||
if(jump > 0) {
|
||||
//cliSerial->printf("Do Jump to %d\n",command_cond_queue.p1);
|
||||
jump--;
|
||||
change_command(command_cond_queue.p1);
|
||||
|
||||
} else if (jump == 0) {
|
||||
//cliSerial->printf("Did last jump\n");
|
||||
// we're done, move along
|
||||
jump = -11;
|
||||
|
||||
} else if (jump == -1) {
|
||||
//cliSerial->printf("jumpForever\n");
|
||||
// repeat forever
|
||||
change_command(command_cond_queue.p1);
|
||||
}
|
||||
|
@ -4,18 +4,14 @@
|
||||
//----------------------------------------
|
||||
static void change_command(uint8_t cmd_index)
|
||||
{
|
||||
//cliSerial->printf("change_command: %d\n",cmd_index );
|
||||
// limit range
|
||||
cmd_index = min(g.command_total - 1, cmd_index);
|
||||
|
||||
// load command
|
||||
struct Location temp = get_cmd_with_index(cmd_index);
|
||||
|
||||
//cliSerial->printf("loading cmd: %d with id:%d\n", cmd_index, temp.id);
|
||||
|
||||
// verify it's a nav command
|
||||
if(temp.id > MAV_CMD_NAV_LAST) {
|
||||
//gcs_send_text_P(SEVERITY_LOW,PSTR("error: non-Nav cmd"));
|
||||
|
||||
}else{
|
||||
// clear out command queue
|
||||
@ -32,13 +28,6 @@ static void change_command(uint8_t cmd_index)
|
||||
// called by 10 Hz loop
|
||||
static void update_commands()
|
||||
{
|
||||
//cliSerial->printf("update_commands: %d\n",increment );
|
||||
// A: if we do not have any commands there is nothing to do
|
||||
// B: We have completed the mission, don't redo the mission
|
||||
// XXX debug
|
||||
//uint8_t tmp = g.command_index.get();
|
||||
//cliSerial->printf("command_index %u \n", tmp);
|
||||
|
||||
if(g.command_total <= 1)
|
||||
return;
|
||||
|
||||
|
@ -765,7 +765,6 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
|
||||
|
||||
if(g.rc_1.radio_in < 500) {
|
||||
while(1) {
|
||||
//cliSerial->printf_P(PSTR("\nNo radio; Check connectors."));
|
||||
delay(1000);
|
||||
// stop here
|
||||
}
|
||||
@ -1180,16 +1179,6 @@ static void report_gyro()
|
||||
// CLI utilities
|
||||
/***************************************************************************/
|
||||
|
||||
/*static void
|
||||
* print_PID(PI * pid)
|
||||
* {
|
||||
* cliSerial->printf_P(PSTR("P: %4.2f, I:%4.2f, IMAX:%ld\n"),
|
||||
* pid->kP(),
|
||||
* pid->kI(),
|
||||
* (long)pid->imax());
|
||||
* }
|
||||
*/
|
||||
|
||||
static void
|
||||
print_radio_values()
|
||||
{
|
||||
|
@ -14,8 +14,6 @@ static int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in te
|
||||
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv);
|
||||
|
||||
// This is the help function
|
||||
// PSTR is an AVR macro to read strings from flash memory
|
||||
// printf_P is a version of print_f that reads from flash memory
|
||||
static int8_t main_menu_help(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Commands:\n"
|
||||
|
@ -24,21 +24,6 @@ static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
|
||||
// This is the help function
|
||||
// PSTR is an AVR macro to read strings from flash memory
|
||||
// printf_P is a version of printf that reads from flash memory
|
||||
/*static int8_t help_test(uint8_t argc, const Menu::arg *argv)
|
||||
* {
|
||||
* cliSerial->printf_P(PSTR("\n"
|
||||
* "Commands:\n"
|
||||
* " radio\n"
|
||||
* " servos\n"
|
||||
* " g_gps\n"
|
||||
* " imu\n"
|
||||
* " battery\n"
|
||||
* "\n"));
|
||||
* }*/
|
||||
|
||||
// Creates a constant array of structs representing menu options
|
||||
// and stores them in Flash memory, not RAM.
|
||||
// User enters the string in the console to call the functions on the right.
|
||||
@ -424,20 +409,6 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
g.rc_6.control_in,
|
||||
g.rc_7.control_in);
|
||||
|
||||
//cliSerial->printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d\n"), (g.rc_1.servo_out / 100), (g.rc_2.servo_out / 100), g.rc_3.servo_out, (g.rc_4.servo_out / 100));
|
||||
|
||||
/*cliSerial->printf_P(PSTR( "min: %d"
|
||||
* "\t in: %d"
|
||||
* "\t pwm_in: %d"
|
||||
* "\t sout: %d"
|
||||
* "\t pwm_out %d\n"),
|
||||
* g.rc_3.radio_min,
|
||||
* g.rc_3.control_in,
|
||||
* g.rc_3.radio_in,
|
||||
* g.rc_3.servo_out,
|
||||
* g.rc_3.pwm_out
|
||||
* );
|
||||
*/
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
}
|
||||
|
@ -144,7 +144,6 @@ void roll_pitch_toy()
|
||||
|
||||
#elif TOY_MIXER == TOY_LINEAR_MIXER
|
||||
roll_rate = -((int32_t)g.rc_2.control_in * (yaw_rate/100)) /30;
|
||||
//cliSerial->printf("roll_rate: %d\n",roll_rate);
|
||||
roll_rate = constrain_int32(roll_rate, -2000, 2000);
|
||||
|
||||
#elif TOY_MIXER == TOY_EXTERNAL_MIXER
|
||||
|
Loading…
Reference in New Issue
Block a user