aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-09-19 18:53:29 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-09-19 18:53:29 +0200
commit291f4f3a33e6428b23624b1ffe12fec1015816cd (patch)
tree0dc7b590081184d46ffa2ad88ba6fbe56a364891 /apps/uORB
parentb0b72b11eb6c112d3fb58385f5681af55dd5605a (diff)
downloadpx4-firmware-291f4f3a33e6428b23624b1ffe12fec1015816cd.tar.gz
px4-firmware-291f4f3a33e6428b23624b1ffe12fec1015816cd.tar.bz2
px4-firmware-291f4f3a33e6428b23624b1ffe12fec1015816cd.zip
Reworked control interface, needs testing / validation
Diffstat (limited to 'apps/uORB')
-rw-r--r--apps/uORB/objects_common.cpp4
-rw-r--r--apps/uORB/topics/vehicle_attitude_setpoint.h17
-rw-r--r--apps/uORB/topics/vehicle_command.h4
-rw-r--r--apps/uORB/topics/vehicle_rates_setpoint.h (renamed from apps/uORB/topics/ardrone_motors_setpoint.h)27
-rw-r--r--apps/uORB/topics/vehicle_status.h2
5 files changed, 27 insertions, 27 deletions
diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp
index 1cad57a43..be85a345a 100644
--- a/apps/uORB/objects_common.cpp
+++ b/apps/uORB/objects_common.cpp
@@ -78,8 +78,8 @@ ORB_DEFINE(vehicle_global_position, struct vehicle_global_position_s);
#include "topics/vehicle_local_position.h"
ORB_DEFINE(vehicle_local_position, struct vehicle_local_position_s);
-#include "topics/ardrone_motors_setpoint.h"
-ORB_DEFINE(ardrone_motors_setpoint, struct ardrone_motors_setpoint_s);
+#include "topics/vehicle_rates_setpoint.h"
+ORB_DEFINE(vehicle_rates_setpoint, struct vehicle_rates_setpoint_s);
#include "topics/rc_channels.h"
ORB_DEFINE(rc_channels, struct rc_channels_s);
diff --git a/apps/uORB/topics/vehicle_attitude_setpoint.h b/apps/uORB/topics/vehicle_attitude_setpoint.h
index 0c33ebff8..62367cf77 100644
--- a/apps/uORB/topics/vehicle_attitude_setpoint.h
+++ b/apps/uORB/topics/vehicle_attitude_setpoint.h
@@ -56,21 +56,18 @@ struct vehicle_attitude_setpoint_s
{
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
- float roll_tait_bryan; /**< Tait-Bryan angle in NED frame */
- float pitch_tait_bryan; /**< Tait-Bryan angle in NED frame */
- float yaw_tait_bryan; /**< Tait-Bryan angle in NED frame */
- float tait_bryan_valid; /**< Set to true if Tait-Bryan angles are valid */
+ //float roll_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ //float pitch_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ //float yaw_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ //float tait_bryan_valid; /**< Set to true if Tait-Bryan angles are valid */
float roll_body; /**< body angle in NED frame */
float pitch_body; /**< body angle in NED frame */
float yaw_body; /**< body angle in NED frame */
- float roll_rate_body; /**< body angle in NED frame */
- float pitch_rate_body; /**< body angle in NED frame */
- float yaw_rate_body; /**< body angle in NED frame */
- float body_valid; /**< Set to true if Tait-Bryan angles are valid */
+ //float body_valid; /**< Set to true if body angles are valid */
- float R_body[9]; /**< Rotation matrix describing the setpoint as rotation from the current body frame */
- bool R_valid; /**< Set to true if rotation matrix is valid */
+ //float R_body[9]; /**< Rotation matrix describing the setpoint as rotation from the current body frame */
+ //bool R_valid; /**< Set to true if rotation matrix is valid */
float thrust; /**< Thrust in Newton the power system should generate */
diff --git a/apps/uORB/topics/vehicle_command.h b/apps/uORB/topics/vehicle_command.h
index dca928efd..3e220965d 100644
--- a/apps/uORB/topics/vehicle_command.h
+++ b/apps/uORB/topics/vehicle_command.h
@@ -50,6 +50,10 @@
* @{
*/
+enum PX4_CMD {
+ PX4_CMD_CONTROLLER_SELECTION = 1000,
+};
+
struct vehicle_command_s
{
float param1; /**< Parameter 1, as defined by MAVLink MAV_CMD enum. */
diff --git a/apps/uORB/topics/ardrone_motors_setpoint.h b/apps/uORB/topics/vehicle_rates_setpoint.h
index d0cb0ad73..3400e5399 100644
--- a/apps/uORB/topics/ardrone_motors_setpoint.h
+++ b/apps/uORB/topics/vehicle_rates_setpoint.h
@@ -33,12 +33,12 @@
****************************************************************************/
/**
- * @file ardrone_motors_setpoint.h
- * Definition of the ardrone_motors_setpoint uORB topic.
+ * @file vehicle_rates_setpoint.h
+ * Definition of the vehicle rates setpoint topic
*/
-#ifndef TOPIC_ARDRONE_MOTORS_SETPOINT_H_
-#define TOPIC_ARDRONE_MOTORS_SETPOINT_H_
+#ifndef TOPIC_VEHICLE_RATES_SETPOINT_H_
+#define TOPIC_VEHICLE_RATES_SETPOINT_H_
#include <stdint.h>
#include "../uORB.h"
@@ -48,23 +48,22 @@
* @{
*/
-struct ardrone_motors_setpoint_s
+struct vehicle_rates_setpoint_s
{
- uint64_t timestamp; //in microseconds since system start, is set whenever the writing thread stores new data
+ uint64_t timestamp; /**< in microseconds since system start */
- 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 */
+ float roll; /**< body angular rates in NED frame */
+ float pitch; /**< body angular rates in NED frame */
+ float yaw; /**< body angular rates in NED frame */
+ float thrust; /**< thrust normalized to 0..1 */
+
+}; /**< vehicle_rates_setpoint */
/**
* @}
*/
/* register this as object request broker structure */
-ORB_DECLARE(ardrone_motors_setpoint);
+ORB_DECLARE(vehicle_rates_setpoint);
#endif
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index cfde2ab53..850029f01 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -127,7 +127,7 @@ struct vehicle_status_s
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool flag_control_speed_enabled; /**< true if speed (implies direction) is controlled */
+ bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
bool flag_control_position_enabled; /**< true if position is controlled */
bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */