aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-07-23 09:31:28 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-07-23 09:31:28 +0200
commit825b84fa3bbf07bfaa5d664a634c77b4ab5ac4cb (patch)
tree617447ca54a0b47fef1777e2a8c05746f5210a91 /src/modules/uORB
parent8bb1f9a4bf3fae0cf8db9a598b4fb1036a9514dd (diff)
parenta7d2963e2bca060493f787cf637b0e1b0d9d829e (diff)
downloadpx4-firmware-825b84fa3bbf07bfaa5d664a634c77b4ab5ac4cb.tar.gz
px4-firmware-825b84fa3bbf07bfaa5d664a634c77b4ab5ac4cb.tar.bz2
px4-firmware-825b84fa3bbf07bfaa5d664a634c77b4ab5ac4cb.zip
Merge remote-tracking branch 'upstream/master' into offboard2_externalsetpointmessages
Conflicts: src/modules/mavlink/mavlink_main.cpp
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/topics/actuator_armed.h3
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h2
-rw-r--r--src/modules/uORB/topics/tecs_status.h1
-rw-r--r--src/modules/uORB/topics/telemetry_status.h3
-rw-r--r--src/modules/uORB/topics/vehicle_command.h1
5 files changed, 8 insertions, 2 deletions
diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h
index a98d3fc3a..0f6c9aca1 100644
--- a/src/modules/uORB/topics/actuator_armed.h
+++ b/src/modules/uORB/topics/actuator_armed.h
@@ -56,6 +56,7 @@ struct actuator_armed_s {
bool armed; /**< Set to true if system is armed */
bool ready_to_arm; /**< Set to true if system is ready to be armed */
bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
+ bool force_failsafe; /**< Set to true if the actuators are forced to the failsafe position */
};
/**
@@ -65,4 +66,4 @@ struct actuator_armed_s {
/* register this as object request broker structure */
ORB_DECLARE(actuator_armed);
-#endif \ No newline at end of file
+#endif
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index 673c0e491..4a1932180 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -95,6 +95,8 @@ struct position_setpoint_triplet_s
struct position_setpoint_s previous;
struct position_setpoint_s current;
struct position_setpoint_s next;
+
+ unsigned nav_state; /**< report the navigation state */
};
/**
diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h
index c4d0c1874..33055018c 100644
--- a/src/modules/uORB/topics/tecs_status.h
+++ b/src/modules/uORB/topics/tecs_status.h
@@ -66,6 +66,7 @@ struct tecs_status_s {
float altitudeSp;
float altitude;
+ float altitudeFiltered;
float flightPathAngleSp;
float flightPathAngle;
float flightPathAngleFiltered;
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index 3347724a5..1297c1a9d 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -57,7 +57,8 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
struct telemetry_status_s {
uint64_t timestamp;
- uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */
+ uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */
+ uint64_t telem_time; /**< Time of last received telemetry status packet, 0 for none */
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
uint8_t rssi; /**< local signal strength */
uint8_t remote_rssi; /**< remote signal strength */
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index faf8cc7db..84503887d 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -79,6 +79,7 @@ enum VEHICLE_CMD {
VEHICLE_CMD_DO_REPEAT_RELAY = 182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_SET_SERVO = 183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
VEHICLE_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */