aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp44
-rw-r--r--src/modules/mavlink/mavlink_receiver.h3
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c59
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c8
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h13
-rw-r--r--src/modules/uORB/objects_common.cpp3
-rw-r--r--src/modules/uORB/topics/vision_position_estimate.h82
7 files changed, 203 insertions, 9 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 99ec98ee9..43a7abdda 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -106,6 +106,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_att_sp_pub(-1),
_rates_sp_pub(-1),
_vicon_position_pub(-1),
+ _vision_position_pub(-1),
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
@@ -149,6 +150,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_vicon_position_estimate(msg);
break;
+ case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
+ handle_message_vision_position_estimate(msg);
+ break;
+
case MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST:
handle_message_quad_swarm_roll_pitch_yaw_thrust(msg);
break;
@@ -363,6 +368,45 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
}
void
+MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
+{
+ mavlink_vision_position_estimate_t pos;
+ mavlink_msg_vision_position_estimate_decode(msg, &pos);
+
+ struct vision_position_estimate vision_position;
+ memset(&vision_position, 0, sizeof(vision_position));
+
+ // Use the component ID to identify the vision sensor
+ vision_position.id = msg->compid;
+
+ vision_position.timestamp_boot = hrt_absolute_time();
+ vision_position.timestamp_computer = pos.usec;
+ vision_position.x = pos.x;
+ vision_position.y = pos.y;
+ vision_position.z = pos.z;
+
+ // XXX fis this
+ vision_position.vx = 0.0f;
+ vision_position.vy = 0.0f;
+ vision_position.vz = 0.0f;
+
+ math::Quaternion q;
+ q.from_euler(pos.roll, pos.pitch, pos.yaw);
+
+ vision_position.q[0] = q(0);
+ vision_position.q[1] = q(1);
+ vision_position.q[2] = q(2);
+ vision_position.q[3] = q(3);
+
+ if (_vision_position_pub < 0) {
+ _vision_position_pub = orb_advertise(ORB_ID(vision_position_estimate), &vision_position);
+
+ } else {
+ orb_publish(ORB_ID(vision_position_estimate), _vision_position_pub, &vision_position);
+ }
+}
+
+void
MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg)
{
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control;
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 8d38b9973..a94307705 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -58,6 +58,7 @@
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/optical_flow.h>
@@ -112,6 +113,7 @@ private:
void handle_message_optical_flow(mavlink_message_t *msg);
void handle_message_set_mode(mavlink_message_t *msg);
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
+ void handle_message_vision_position_estimate(mavlink_message_t *msg);
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
void handle_message_radio_status(mavlink_message_t *msg);
void handle_message_manual_control(mavlink_message_t *msg);
@@ -145,6 +147,7 @@ private:
orb_advert_t _att_sp_pub;
orb_advert_t _rates_sp_pub;
orb_advert_t _vicon_position_pub;
+ orb_advert_t _vision_position_pub;
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 05eae047c..71abcc170 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -59,6 +59,7 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/optical_flow.h>
#include <mavlink/mavlink_log.h>
@@ -80,6 +81,7 @@ static bool thread_running = false; /**< Deamon status flag */
static int position_estimator_inav_task; /**< Handle of deamon task / thread */
static bool verbose_mode = false;
+static const hrt_abstime vision_topic_timeout = 500000; // Vision topic timeout = 0.5s
static const hrt_abstime gps_topic_timeout = 500000; // GPS topic timeout = 0.5s
static const hrt_abstime flow_topic_timeout = 1000000; // optical flow topic timeout = 1s
static const hrt_abstime sonar_timeout = 150000; // sonar timeout = 150ms
@@ -294,6 +296,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
bool sonar_valid = false; // sonar is valid
bool flow_valid = false; // flow is valid
bool flow_accurate = false; // flow should be accurate (this flag not updated if flow_valid == false)
+ bool vision_valid = false;
/* declare and safely initialize all structs */
struct actuator_controls_s actuator;
@@ -312,6 +315,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
memset(&local_pos, 0, sizeof(local_pos));
struct optical_flow_s flow;
memset(&flow, 0, sizeof(flow));
+ struct vision_position_estimate vision;
+ memset(&vision, 0, sizeof(vision));
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
@@ -323,6 +328,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
int optical_flow_sub = orb_subscribe(ORB_ID(optical_flow));
int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ int vision_position_estimate_sub = orb_subscribe(ORB_ID(vision_position_estimate));
int home_position_sub = orb_subscribe(ORB_ID(home_position));
/* advertise */
@@ -616,6 +622,46 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
+
+ /* check no vision circuit breaker is set */
+ if (params.no_vision != CBRK_NO_VISION_KEY) {
+ /* vehicle vision position */
+ orb_check(vision_position_estimate_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vision_position_estimate), vision_position_estimate_sub, &vision);
+
+ /* reset position estimate on first vision update */
+ if (!vision_valid) {
+ x_est[0] = vision.x;
+ x_est[1] = vision.vx;
+ y_est[0] = vision.y;
+ y_est[1] = vision.vy;
+ z_est[0] = vision.z;
+ z_est[1] = vision.vz;
+
+ vision_valid = true;
+ }
+
+ /* calculate correction for position */
+ corr_gps[0][0] = vision.x - x_est[0];
+ corr_gps[1][0] = vision.y - y_est[0];
+ corr_gps[2][0] = vision.z - z_est[0];
+
+ /* calculate correction for velocity */
+ corr_gps[0][1] = vision.vx - x_est[1];
+ corr_gps[1][1] = vision.vy - y_est[1];
+ corr_gps[2][1] = vision.vz - z_est[1];
+
+ eph = 0.05f;
+ epv = 0.05f;
+
+ w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, eph);
+ w_gps_z = min_eph_epv / fmaxf(min_eph_epv, epv);
+
+ }
+ }
+
/* vehicle GPS position */
orb_check(vehicle_gps_position_sub, &updated);
@@ -738,6 +784,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
mavlink_log_info(mavlink_fd, "[inav] GPS timeout");
}
+ /* check for timeout on vision topic */
+ if (vision_valid && t > vision.timestamp_boot + vision_topic_timeout) {
+ vision_valid = false;
+ warnx("VISION timeout");
+ mavlink_log_info(mavlink_fd, "[inav] VISION timeout");
+ }
+
/* check for sonar measurement timeout */
if (sonar_valid && t > sonar_time + sonar_timeout) {
corr_sonar = 0.0f;
@@ -757,12 +810,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
/* use GPS if it's valid and reference position initialized */
- bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
- bool use_gps_z = ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W;
+ bool use_gps_xy = (ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W) || vision_valid;
+ bool use_gps_z = (ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W) || vision_valid;
/* use flow if it's valid and (accurate or no GPS available) */
bool use_flow = flow_valid && (flow_accurate || !use_gps_xy);
- bool can_estimate_xy = (eph < max_eph_epv) || use_gps_xy || use_flow;
+ bool can_estimate_xy = (eph < max_eph_epv) || use_gps_xy || use_flow || vision_valid;
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index 0581f8236..0d9fbef27 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +34,8 @@
/*
* @file position_estimator_inav_params.c
*
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ *
* Parameters for position_estimator_inav
*/
@@ -56,6 +57,7 @@ PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f);
+PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f);
int parameters_init(struct position_estimator_inav_param_handles *h)
@@ -76,6 +78,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
h->land_t = param_find("INAV_LAND_T");
h->land_disp = param_find("INAV_LAND_DISP");
h->land_thr = param_find("INAV_LAND_THR");
+ h->no_vision = param_find("CBRK_NO_VISION");
h->delay_gps = param_find("INAV_DELAY_GPS");
return OK;
@@ -99,6 +102,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
param_get(h->land_t, &(p->land_t));
param_get(h->land_disp, &(p->land_disp));
param_get(h->land_thr, &(p->land_thr));
+ param_get(h->no_vision, &(p->no_vision));
param_get(h->delay_gps, &(p->delay_gps));
return OK;
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index 423f0d879..08098d6c3 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,9 +32,11 @@
****************************************************************************/
/*
- * @file position_estimator_inav_params.h
+ * @file position_estimator_inav_params.c
*
- * Parameters for Position Estimator
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Parameters definition for position_estimator_inav
*/
#include <systemlib/param/param.h>
@@ -57,6 +58,7 @@ struct position_estimator_inav_params {
float land_t;
float land_disp;
float land_thr;
+ int32_t no_vision;
float delay_gps;
};
@@ -77,9 +79,12 @@ struct position_estimator_inav_param_handles {
param_t land_t;
param_t land_disp;
param_t land_thr;
+ param_t no_vision;
param_t delay_gps;
};
+#define CBRK_NO_VISION_KEY 328754
+
/**
* Initialize all parameter handles and values
*
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index c5831462b..7b1b162a0 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -206,6 +206,9 @@ ORB_DEFINE(encoders, struct encoders_s);
#include "topics/estimator_status.h"
ORB_DEFINE(estimator_status, struct estimator_status_report);
+#include "topics/vision_position_estimate.h"
+ORB_DEFINE(vision_position_estimate, struct vision_position_estimate);
+
#include "topics/vehicle_force_setpoint.h"
ORB_DEFINE(vehicle_force_setpoint, struct vehicle_force_setpoint_s);
diff --git a/src/modules/uORB/topics/vision_position_estimate.h b/src/modules/uORB/topics/vision_position_estimate.h
new file mode 100644
index 000000000..74c96cf2e
--- /dev/null
+++ b/src/modules/uORB/topics/vision_position_estimate.h
@@ -0,0 +1,82 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * 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 vision_position_estimate.h
+ * Vision based position estimate
+ */
+
+#ifndef TOPIC_VISION_POSITION_ESTIMATE_H_
+#define TOPIC_VISION_POSITION_ESTIMATE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Vision based position estimate in NED frame
+ */
+struct vision_position_estimate {
+
+ unsigned id; /**< ID of the estimator, commonly the component ID of the incoming message */
+
+ uint64_t timestamp_boot; /**< time of this estimate, in microseconds since system start */
+ uint64_t timestamp_computer; /**< timestamp provided by the companion computer, in us */
+
+ float x; /**< X position in meters in NED earth-fixed frame */
+ float y; /**< Y position in meters in NED earth-fixed frame */
+ float z; /**< Z position in meters in NED earth-fixed frame (negative altitude) */
+
+ float vx; /**< X velocity in meters per second in NED earth-fixed frame */
+ float vy; /**< Y velocity in meters per second in NED earth-fixed frame */
+ float vz; /**< Z velocity in meters per second in NED earth-fixed frame */
+
+ float q[4]; /**< Estimated attitude as quaternion */
+
+ // XXX Add covariances here
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vision_position_estimate);
+
+#endif /* TOPIC_VISION_POSITION_ESTIMATE_H_ */