aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-09-18 18:28:49 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-09-18 18:28:49 +0200
commitb0b72b11eb6c112d3fb58385f5681af55dd5605a (patch)
treeb5c9548cc4619919fab7015df2a390de70578ac3 /apps/uORB
parent3816327977166cbb68ba94aae4b316651cd70ba3 (diff)
parentdf034330340aa1f938adbc1ed8840689ead41d89 (diff)
downloadpx4-firmware-b0b72b11eb6c112d3fb58385f5681af55dd5605a.tar.gz
px4-firmware-b0b72b11eb6c112d3fb58385f5681af55dd5605a.tar.bz2
px4-firmware-b0b72b11eb6c112d3fb58385f5681af55dd5605a.zip
Reworking control infrastructure for inner rate loop, preparing offboard interface
Diffstat (limited to 'apps/uORB')
-rw-r--r--apps/uORB/topics/ardrone_motors_setpoint.h12
-rw-r--r--apps/uORB/topics/vehicle_status.h19
2 files changed, 16 insertions, 15 deletions
diff --git a/apps/uORB/topics/ardrone_motors_setpoint.h b/apps/uORB/topics/ardrone_motors_setpoint.h
index 54d81b706..d0cb0ad73 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 */
/**
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index 713a7a801..cfde2ab53 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -111,23 +111,24 @@ struct vehicle_status_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 */
- commander_state_machine_t state_machine; /**< Current flight state, main state machine */
- enum VEHICLE_FLIGHT_MODE flight_mode; /**< Current flight mode, as defined by mode switch */
- enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< Current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
+ commander_state_machine_t state_machine; /**< current flight state, main state machine */
+ enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
+ enum VEHICLE_ATTITUDE_MODE attitute_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
// uint8_t mode;
/* system flags - these represent the state predicates */
- bool flag_system_armed; /**< True is motors / actuators are armed */
+ bool flag_system_armed; /**< true is motors / actuators are armed */
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_hil_enabled; /**< True if hardware in the loop simulation is enabled */
+ bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
- // bool flag_control_rates_enabled; /**< true if rates are stabilized */
- // bool flag_control_attitude_enabled; *< true if attitude stabilization is mixed in
- // bool control_speed_enabled; /**< true if speed (implies direction) is controlled */
- // bool control_position_enabled; /**< true if position is controlled */
+ 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_position_enabled; /**< true if position is controlled */
bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */