aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorTickTock- <lukecell@safe-mail.net>2014-04-27 12:43:13 -0700
committerTickTock- <lukecell@safe-mail.net>2014-04-27 12:43:13 -0700
commit07c35010aaee59fbed21824c20666bda9c340705 (patch)
tree87d29034e772e2f5b18cbaab5478b65daa5bb930 /src/modules/mavlink
parentb4d30e53c5af47a90d98c4c058df6a645ca34d40 (diff)
parentad77ba26427aa9a2d8b8241fc95271667a1c0863 (diff)
downloadpx4-firmware-07c35010aaee59fbed21824c20666bda9c340705.tar.gz
px4-firmware-07c35010aaee59fbed21824c20666bda9c340705.tar.bz2
px4-firmware-07c35010aaee59fbed21824c20666bda9c340705.zip
Merged in upstream master
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink.c6
-rw-r--r--src/modules/mavlink/mavlink_main.cpp14
-rw-r--r--src/modules/mavlink/mavlink_main.h3
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp49
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp22
-rw-r--r--src/modules/mavlink/module.mk2
6 files changed, 89 insertions, 7 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index ad435b251..e49288a74 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -62,6 +62,12 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
+/**
+ * Use/Accept HIL GPS message (even if not in HIL mode)
+ * If set to 1 incomming HIL GPS messages are parsed.
+ * @group MAVLink
+ */
+PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
mavlink_system_t mavlink_system = {
100,
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 2416a1264..7ecca0d65 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -208,6 +208,7 @@ Mavlink::Mavlink() :
_mavlink_fd(-1),
_task_running(false),
_hil_enabled(false),
+ _use_hil_gps(false),
_is_usb_uart(false),
_wait_to_transmit(false),
_received_messages(false),
@@ -487,11 +488,13 @@ void Mavlink::mavlink_update_system(void)
static param_t param_system_id;
static param_t param_component_id;
static param_t param_system_type;
+ static param_t param_use_hil_gps;
if (!initialized) {
param_system_id = param_find("MAV_SYS_ID");
param_component_id = param_find("MAV_COMP_ID");
param_system_type = param_find("MAV_TYPE");
+ param_use_hil_gps = param_find("MAV_USEHILGPS");
initialized = true;
}
@@ -516,6 +519,11 @@ void Mavlink::mavlink_update_system(void)
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
mavlink_system.type = system_type;
}
+
+ int32_t use_hil_gps;
+ param_get(param_use_hil_gps, &use_hil_gps);
+
+ _use_hil_gps = (bool)use_hil_gps;
}
int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_config_original, bool *is_usb)
@@ -574,6 +582,11 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
/* open uart */
_uart_fd = open(uart_name, O_RDWR | O_NOCTTY);
+ if (_uart_fd < 0) {
+ return _uart_fd;
+ }
+
+
/* Try to set baud rate */
struct termios uart_config;
int termios_state;
@@ -1953,6 +1966,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult);
configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f * rate_mult);
configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f * rate_mult);
+ configure_stream("DISTANCE_SENSOR", 0.5f);
break;
case MAVLINK_MODE_CAMERA:
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 66d82b471..1bf51fd31 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -157,6 +157,8 @@ public:
bool get_hil_enabled() { return _hil_enabled; }
+ bool get_use_hil_gps() { return _use_hil_gps; }
+
bool get_flow_control_enabled() { return _flow_control_enabled; }
bool get_forwarding_on() { return _forwarding_on; }
@@ -223,6 +225,7 @@ private:
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
+ bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
bool _is_usb_uart; /**< Port is USB */
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
bool _received_messages; /**< Whether we've received valid mavlink messages. */
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 648228e3b..678ce1645 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -72,6 +72,7 @@
#include <uORB/topics/navigation_capabilities.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
+#include <drivers/drv_range_finder.h>
#include "mavlink_messages.h"
@@ -270,7 +271,7 @@ protected:
status->load * 1000.0f,
status->battery_voltage * 1000.0f,
status->battery_current * 1000.0f,
- status->battery_remaining,
+ status->battery_remaining * 100.0f,
status->drop_rate_comm,
status->errors_comm,
status->errors_count1,
@@ -1312,6 +1313,51 @@ protected:
}
};
+class MavlinkStreamDistanceSensor : public MavlinkStream
+{
+public:
+ const char *get_name()
+ {
+ return "DISTANCE_SENSOR";
+ }
+
+ MavlinkStream *new_instance()
+ {
+ return new MavlinkStreamDistanceSensor();
+ }
+
+private:
+ MavlinkOrbSubscription *range_sub;
+ struct range_finder_report *range;
+
+protected:
+ void subscribe(Mavlink *mavlink)
+ {
+ range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder));
+ range = (struct range_finder_report *)range_sub->get_data();
+ }
+
+ void send(const hrt_abstime t)
+ {
+ (void)range_sub->update(t);
+
+ uint8_t type;
+
+ switch (range->type) {
+ case RANGE_FINDER_TYPE_LASER:
+ type = MAV_DISTANCE_SENSOR_LASER;
+ break;
+ }
+
+ uint8_t id = 0;
+ uint8_t orientation = 0;
+ uint8_t covariance = 20;
+
+ mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
+ range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
+ }
+};
+
MavlinkStream *streams_list[] = {
new MavlinkStreamHeartbeat(),
new MavlinkStreamSysStatus(),
@@ -1338,6 +1384,7 @@ MavlinkStream *streams_list[] = {
new MavlinkStreamAttitudeControls(),
new MavlinkStreamNamedValueFloat(),
new MavlinkStreamCameraCapture(),
+ new MavlinkStreamDistanceSensor(),
new MavlinkStreamViconPositionEstimate(),
nullptr
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 0762b76f2..33a4fef12 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -160,6 +160,9 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
* The HIL mode is enabled by the HIL bit flag
* in the system mode. Either send a set mode
* COMMAND_LONG message or a SET_MODE message
+ *
+ * Accept HIL GPS messages if use_hil_gps flag is true.
+ * This allows to provide fake gps measurements to the system.
*/
if (_mavlink->get_hil_enabled()) {
switch (msg->msgid) {
@@ -167,10 +170,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_hil_sensor(msg);
break;
- case MAVLINK_MSG_ID_HIL_GPS:
- handle_message_hil_gps(msg);
- break;
-
case MAVLINK_MSG_ID_HIL_STATE_QUATERNION:
handle_message_hil_state_quaternion(msg);
break;
@@ -180,7 +179,20 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
}
}
- /* If we've received a valid message, mark the flag indicating so.
+
+ if (_mavlink->get_hil_enabled() || (_mavlink->get_use_hil_gps() && msg->sysid == mavlink_system.sysid)) {
+ switch (msg->msgid) {
+ case MAVLINK_MSG_ID_HIL_GPS:
+ handle_message_hil_gps(msg);
+ break;
+
+ default:
+ break;
+ }
+
+ }
+
+ /* If we've received a valid message, mark the flag indicating so.
This is used in the '-w' command-line flag. */
_mavlink->set_has_received_messages(true);
}
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index c44354ff0..dcca11977 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -47,4 +47,4 @@ SRCS += mavlink_main.cpp \
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
-MAXOPTIMIZATION = -Os
+MAXOPTIMIZATION = -Os