aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-06-17 14:44:45 +0400
committerAnton Babushkin <anton.babushkin@me.com>2013-06-17 14:44:45 +0400
commit22a925adeb2cae7496c31da35cd5f93d2993c01f (patch)
tree62584c904a420e0a4a448db757f41126341c6bd4 /src/modules
parent138ce117ab0a9b95f473f34ce8644fa6456b32a6 (diff)
parentbadaa5e4a23561834ff4badbe3a62fbf3d3e02aa (diff)
downloadpx4-firmware-22a925adeb2cae7496c31da35cd5f93d2993c01f.tar.gz
px4-firmware-22a925adeb2cae7496c31da35cd5f93d2993c01f.tar.bz2
px4-firmware-22a925adeb2cae7496c31da35cd5f93d2993c01f.zip
Merge branch 'master' into sdlog2
Diffstat (limited to 'src/modules')
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp2
-rw-r--r--src/modules/sdlog2/sdlog2.c19
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h8
-rw-r--r--src/modules/uORB/objects_common.cpp6
-rw-r--r--src/modules/uORB/topics/filtered_bottom_flow.h74
-rw-r--r--src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h69
6 files changed, 176 insertions, 2 deletions
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 8e18c3c9a..16d5ad626 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -126,7 +126,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 12400,
+ 14000,
attitude_estimator_ekf_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index f67cfad87..178986f61 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -241,7 +241,7 @@ int sdlog2_main(int argc, char *argv[])
deamon_task = task_spawn("sdlog2",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30,
- 2048,
+ 3000,
sdlog2_thread_main,
(const char **)argv);
exit(0);
@@ -661,6 +661,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int vicon_pos_sub;
int flow_sub;
int rc_sub;
+ int airspeed_sub;
} subs;
/* log message buffer: header + body */
@@ -680,6 +681,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_STAT_s log_STAT;
struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0;
+ struct log_AIRS_s log_AIRS;
struct log_ARSP_s log_ARSP;
} body;
} log_msg = {
@@ -784,6 +786,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- AIRSPEED --- */
+ subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ fds[fdsc_count].fd = subs.airspeed_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* WARNING: If you get the error message below,
* then the number of registered messages (fdsc)
* differs from the number of messages in the above list.
@@ -1070,6 +1078,15 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(RC);
}
+ /* --- AIRSPEED --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed);
+ log_msg.msg_type = LOG_AIRS_MSG;
+ log_msg.body.log_AIRS.indicated_airspeed = buf.airspeed.indicated_airspeed_m_s;
+ log_msg.body.log_AIRS.true_airspeed = buf.airspeed.true_airspeed_m_s;
+ LOGBUFFER_WRITE_AND_COUNT(AIRS);
+ }
+
/* signal the other thread new data, but not yet unlock */
if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
#ifdef SDLOG2_DEBUG
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index fc5687988..efb999a50 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -172,6 +172,13 @@ struct log_OUT0_s {
float output[8];
};
+/* --- AIRS - AIRSPEED --- */
+#define LOG_AIRS_MSG 13
+struct log_AIRS_s {
+ float indicated_airspeed;
+ float true_airspeed;
+};
+
/* --- ARSP - ATTITUDE RATE SET POINT --- */
#define LOG_ARSP_MSG 13
struct log_ARSP_s {
@@ -196,6 +203,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"),
LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
+ LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
};
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 4197f6fb2..e22b58cad 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -101,6 +101,9 @@ ORB_DEFINE(vehicle_command, struct vehicle_command_s);
#include "topics/vehicle_local_position_setpoint.h"
ORB_DEFINE(vehicle_local_position_setpoint, struct vehicle_local_position_setpoint_s);
+#include "topics/vehicle_bodyframe_speed_setpoint.h"
+ORB_DEFINE(vehicle_bodyframe_speed_setpoint, struct vehicle_bodyframe_speed_setpoint_s);
+
#include "topics/vehicle_global_position_setpoint.h"
ORB_DEFINE(vehicle_global_position_setpoint, struct vehicle_global_position_setpoint_s);
@@ -119,6 +122,9 @@ ORB_DEFINE(offboard_control_setpoint, struct offboard_control_setpoint_s);
#include "topics/optical_flow.h"
ORB_DEFINE(optical_flow, struct optical_flow_s);
+#include "topics/filtered_bottom_flow.h"
+ORB_DEFINE(filtered_bottom_flow, struct filtered_bottom_flow_s);
+
#include "topics/omnidirectional_flow.h"
ORB_DEFINE(omnidirectional_flow, struct omnidirectional_flow_s);
diff --git a/src/modules/uORB/topics/filtered_bottom_flow.h b/src/modules/uORB/topics/filtered_bottom_flow.h
new file mode 100644
index 000000000..ab6de2613
--- /dev/null
+++ b/src/modules/uORB/topics/filtered_bottom_flow.h
@@ -0,0 +1,74 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file filtered_bottom_flow.h
+ * Definition of the filtered bottom flow uORB topic.
+ */
+
+#ifndef TOPIC_FILTERED_BOTTOM_FLOW_H_
+#define TOPIC_FILTERED_BOTTOM_FLOW_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Filtered bottom flow in bodyframe.
+ */
+struct filtered_bottom_flow_s
+{
+ uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
+
+ float sumx; /**< Integrated bodyframe x flow in meters */
+ float sumy; /**< Integrated bodyframe y flow in meters */
+
+ float vx; /**< Flow bodyframe x speed, m/s */
+ float vy; /**< Flow bodyframe y Speed, m/s */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(filtered_bottom_flow);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h b/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
new file mode 100644
index 000000000..fbfab09f3
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
@@ -0,0 +1,69 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
+ * Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_bodyframe_speed_setpoint.h
+ * Definition of the bodyframe speed setpoint uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_BODYFRAME_SPEED_SETPOINT_H_
+#define TOPIC_VEHICLE_BODYFRAME_SPEED_SETPOINT_H_
+
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct vehicle_bodyframe_speed_setpoint_s
+{
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+
+ float vx; /**< in m/s */
+ float vy; /**< in m/s */
+// float vz; /**< in m/s */
+ float thrust_sp;
+ float yaw_sp; /**< in radian -PI +PI */
+}; /**< Speed in bodyframe to go to */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_bodyframe_speed_setpoint);
+
+#endif