aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink/mavlink_parameters.h
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-08-20 09:07:33 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-08-20 09:07:33 +0200
commit2c8fafd12af505f0f6dbcce521c99f7cd76109ca (patch)
treea4fbfbb6ce3662c1e7df37240e281f05bbe13d19 /apps/mavlink/mavlink_parameters.h
parent4a7f92fad0f5f7170038690e3e35af889bddae78 (diff)
downloadpx4-firmware-2c8fafd12af505f0f6dbcce521c99f7cd76109ca.tar.gz
px4-firmware-2c8fafd12af505f0f6dbcce521c99f7cd76109ca.tar.bz2
px4-firmware-2c8fafd12af505f0f6dbcce521c99f7cd76109ca.zip
Reworked MAVLink parameter interface to support new parameter storage, tested.
Diffstat (limited to 'apps/mavlink/mavlink_parameters.h')
-rw-r--r--apps/mavlink/mavlink_parameters.h44
1 files changed, 41 insertions, 3 deletions
diff --git a/apps/mavlink/mavlink_parameters.h b/apps/mavlink/mavlink_parameters.h
index e32732f58..e136d69bc 100644
--- a/apps/mavlink/mavlink_parameters.h
+++ b/apps/mavlink/mavlink_parameters.h
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author 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
@@ -43,6 +43,44 @@
#include "v1.0/common/mavlink.h"
#include <stdbool.h>
+#include <systemlib/param/param.h>
+/**
+ * Handle parameter related messages.
+ */
void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
-void mavlink_pm_queued_send(void);
+
+/**
+ * Send all parameters at once.
+ *
+ * This function blocks until all parameters have been sent.
+ * it delays each parameter by the passed amount of microseconds.
+ *
+ * @param delay The delay in us between sending all parameters.
+ */
+void mavlink_pm_send_all_params(unsigned int delay);
+
+/**
+ * Send one parameter.
+ *
+ * @param param The parameter id to send
+ * @return zero on success, nonzero on failure
+ */
+int mavlink_pm_send_param(param_t param);
+
+/**
+ * Send a queue of parameters, one parameter per function call.
+ *
+ * @return zero on success, nonzero on failure
+ */
+ int mavlink_pm_queued_send();
+
+/**
+ * Start sending the parameter queue.
+ *
+ * This function will not directly send parameters, but instead
+ * activate the sending of one parameter on each call of
+ * mavlink_pm_queued_send().
+ * @see mavlink_pm_queued_send()
+ */
+void mavlink_pm_start_queued_send();