Browse Source

g

Signed-off-by: tnaegeli <naegelit@student.ethz.ch>
sbg
tnaegeli 13 years ago
parent
commit
df03433034
  1. 2
      apps/multirotor_att_control/multirotor_att_control_main.c
  2. 14
      apps/uORB/topics/ardrone_motors_setpoint.h
  3. 4
      nuttx/configs/px4fmu/nsh/defconfig

2
apps/multirotor_att_control/multirotor_att_control_main.c

@ -104,7 +104,7 @@ mc_thread_main(int argc, char *argv[]) @@ -104,7 +104,7 @@ mc_thread_main(int argc, char *argv[])
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
//int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
// int setpoint_sub = orb_subscribe(ORB_ID(ardrone_motors_setpoint));
int setpoint_sub = orb_subscribe(ORB_ID(ardrone_motors_setpoint));
/* rate-limit the attitude subscription to 200Hz to pace our loop */
orb_set_interval(att_sub, 5);

14
apps/uORB/topics/ardrone_motors_setpoint.h

@ -50,14 +50,14 @@ @@ -50,14 +50,14 @@
struct ardrone_motors_setpoint_s
{
uint16_t counter; //incremented by the writing thread everytime new data is stored
uint64_t timestamp; //in microseconds since system start, is set whenever the writing thread stores new data
uint16_t motor_front_nw; ///< Front motor in + configuration, front left motor in x configuration
uint16_t motor_right_ne; ///< Right motor in + configuration, front right motor in x configuration
uint16_t motor_back_se; ///< Back motor in + configuration, back right motor in x configuration
uint16_t motor_left_sw; ///< Left motor in + configuration, back left motor in x configuration
uint8_t group; /**< quadrotor group */
uint8_t mode; /**< requested flight mode XXX define */
float p1; /**< parameter 1: rate control: roll rate, att control: roll angle (in radians, NED) */
float p2; /**< parameter 2: rate control: pitch rate, att control: pitch angle (in radians, NED) */
float p3; /**< parameter 3: rate control: yaw rate, att control: yaw angle (in radians, NED) */
float p4; /**< parameter 4: thrust, [0..1] */
}; /**< AR.Drone low level motors */
/**
@ -67,4 +67,4 @@ struct ardrone_motors_setpoint_s @@ -67,4 +67,4 @@ struct ardrone_motors_setpoint_s
/* register this as object request broker structure */
ORB_DECLARE(ardrone_motors_setpoint);
#endif
#endif-\

4
nuttx/configs/px4fmu/nsh/defconfig

@ -236,11 +236,11 @@ CONFIG_AT24XX_MTD_BLOCKSIZE=256 @@ -236,11 +236,11 @@ CONFIG_AT24XX_MTD_BLOCKSIZE=256
CONFIG_SERIAL_TERMIOS=y
CONFIG_SERIAL_CONSOLE_REINIT=y
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART1_SERIAL_CONSOLE=n
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
CONFIG_UART4_SERIAL_CONSOLE=n
CONFIG_UART5_SERIAL_CONSOLE=n
CONFIG_UART5_SERIAL_CONSOLE=y
CONFIG_USART6_SERIAL_CONSOLE=n
#Mavlink messages can be bigger than 128

Loading…
Cancel
Save