aboutsummaryrefslogtreecommitdiff
path: root/apps/ardrone_interface
diff options
context:
space:
mode:
authorJulian Oes <joes@student.ethz.ch>2012-09-27 17:08:29 +0200
committerJulian Oes <joes@student.ethz.ch>2012-09-27 17:08:29 +0200
commit2c5c3141057be1f46cb4a33f71e2331ce36b18a7 (patch)
treec4df8e1d5a005f98d10f215f5645140a4d2d5902 /apps/ardrone_interface
parent7f153098926bf977609c6efb53fa7cb5093564af (diff)
downloadpx4-firmware-2c5c3141057be1f46cb4a33f71e2331ce36b18a7.tar.gz
px4-firmware-2c5c3141057be1f46cb4a33f71e2331ce36b18a7.tar.bz2
px4-firmware-2c5c3141057be1f46cb4a33f71e2331ce36b18a7.zip
Cleanup of lots of debugging printfs
Diffstat (limited to 'apps/ardrone_interface')
-rw-r--r--apps/ardrone_interface/ardrone_interface.c11
-rw-r--r--apps/ardrone_interface/ardrone_motor_control.c4
2 files changed, 2 insertions, 13 deletions
diff --git a/apps/ardrone_interface/ardrone_interface.c b/apps/ardrone_interface/ardrone_interface.c
index 8b4b5c400..8ed6db664 100644
--- a/apps/ardrone_interface/ardrone_interface.c
+++ b/apps/ardrone_interface/ardrone_interface.c
@@ -141,7 +141,6 @@ static int ardrone_open_uart(char *uart_name, struct termios *uart_config_origin
int uart;
/* open uart */
- //printf("[ardrone_interface] UART is %s, baud rate is%d\n",uart_name,speed);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@@ -238,15 +237,14 @@ int ardrone_interface_thread_main(int argc, char *argv[])
/* declare and safely initialize all structs */
struct vehicle_status_s state;
- //memset(&state, 0, sizeof(state));
+ memset(&state, 0, sizeof(state));
struct actuator_controls_s actuator_controls;
- //memset(&actuator_controls, 0, sizeof(actuator_controls));
+ memset(&actuator_controls, 0, sizeof(actuator_controls));
struct actuator_armed_s armed;
armed.armed = false;
/* subscribe to attitude, motor setpoints and system state */
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
-
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
@@ -328,11 +326,6 @@ int ardrone_interface_thread_main(int argc, char *argv[])
* if in failsafe
*/
if (armed.armed && !armed.lockdown) {
-
-
-
- //printf("AMO_BEF: Roll: %4.4f, Pitch: %4.4f, Yaw: %4.4f, Thrust: %4.4f\n",actuator_controls.control[0], actuator_controls.control[1], actuator_controls.control[2], actuator_controls.control[3]);
-
ardrone_mixing_and_output(ardrone_write, &actuator_controls);
} else {
diff --git a/apps/ardrone_interface/ardrone_motor_control.c b/apps/ardrone_interface/ardrone_motor_control.c
index e410d3a71..c68a26df9 100644
--- a/apps/ardrone_interface/ardrone_motor_control.c
+++ b/apps/ardrone_interface/ardrone_motor_control.c
@@ -388,16 +388,12 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
if (motor_thrust <= min_thrust) {
motor_thrust = min_thrust;
output_band = 0.0f;
- //printf("0 silent\n");
} else if (motor_thrust < startpoint_full_control && motor_thrust > min_thrust) {
output_band = band_factor * (motor_thrust - min_thrust);
- //printf("1 starting\n");
} else if (motor_thrust >= startpoint_full_control && motor_thrust < max_thrust - band_factor * startpoint_full_control) {
output_band = band_factor * startpoint_full_control;
- //printf("2 working\n");
} else if (motor_thrust >= max_thrust - band_factor * startpoint_full_control) {
output_band = band_factor * (max_thrust - motor_thrust);
- //printf("3 full\n");
}
//add the yaw, nick and roll components to the basic thrust //TODO:this should be done by the mixer