aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authortnaegeli <naegelit@student.ethz.ch>2012-09-18 13:49:18 +0200
committertnaegeli <naegelit@student.ethz.ch>2012-09-18 13:49:18 +0200
commitdf034330340aa1f938adbc1ed8840689ead41d89 (patch)
tree1d5c9155c185878e0de3e5c1c5aae345bb96db5c
parent5a8dda3343bc35e93015629590ea83bf362c6845 (diff)
downloadpx4-firmware-df034330340aa1f938adbc1ed8840689ead41d89.tar.gz
px4-firmware-df034330340aa1f938adbc1ed8840689ead41d89.tar.bz2
px4-firmware-df034330340aa1f938adbc1ed8840689ead41d89.zip
g
Signed-off-by: tnaegeli <naegelit@student.ethz.ch>
-rw-r--r--apps/multirotor_att_control/multirotor_att_control_main.c2
-rw-r--r--apps/uORB/topics/ardrone_motors_setpoint.h14
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig4
3 files changed, 10 insertions, 10 deletions
diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c
index 3fb505174..408f7e390 100644
--- a/apps/multirotor_att_control/multirotor_att_control_main.c
+++ b/apps/multirotor_att_control/multirotor_att_control_main.c
@@ -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);
diff --git a/apps/uORB/topics/ardrone_motors_setpoint.h b/apps/uORB/topics/ardrone_motors_setpoint.h
index 54d81b706..d1f42cd2c 100644
--- a/apps/uORB/topics/ardrone_motors_setpoint.h
+++ b/apps/uORB/topics/ardrone_motors_setpoint.h
@@ -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
/* register this as object request broker structure */
ORB_DECLARE(ardrone_motors_setpoint);
-#endif
+#endif-\
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index bc1543d56..8d5bbf898 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -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