Browse Source

changed headers

sbg
Thomas Gubler 12 years ago
parent
commit
56f4849e87
  1. 2
      apps/fixedwing_att_control/fixedwing_att_control_att.c
  2. 3
      apps/fixedwing_att_control/fixedwing_att_control_main.c
  3. 3
      apps/fixedwing_att_control/fixedwing_att_control_rate.c
  4. 2
      apps/fixedwing_pos_control/fixedwing_pos_control_main.c

2
apps/fixedwing_att_control/fixedwing_att_control_att.c

@ -47,7 +47,7 @@ @@ -47,7 +47,7 @@
#include <math.h>
#include <poll.h>
#include <time.h>
#include <arch/board/up_hrt.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>

3
apps/fixedwing_att_control/fixedwing_att_control_main.c

@ -46,7 +46,7 @@ @@ -46,7 +46,7 @@
#include <math.h>
#include <poll.h>
#include <time.h>
#include <arch/board/up_hrt.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_global_position.h>
@ -194,6 +194,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[]) @@ -194,6 +194,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
/* kill all outputs */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
actuators.control[i] = 0.0f;
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);

3
apps/fixedwing_att_control/fixedwing_att_control_rate.c

@ -47,7 +47,7 @@ @@ -47,7 +47,7 @@
#include <math.h>
#include <poll.h>
#include <time.h>
#include <arch/board/up_hrt.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
@ -178,6 +178,7 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp, @@ -178,6 +178,7 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
parameters_update(&h, &p);
}
/* Roll Rate (PI) */
actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0, deltaT);

2
apps/fixedwing_pos_control/fixedwing_pos_control_main.c

@ -46,7 +46,7 @@ @@ -46,7 +46,7 @@
#include <math.h>
#include <poll.h>
#include <time.h>
#include <arch/board/up_hrt.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_global_position.h>

Loading…
Cancel
Save