aboutsummaryrefslogtreecommitdiff
path: root/src/examples/subscriber
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-03 14:43:03 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-03 14:43:03 +0100
commit1c79f0cef1f21cff7935ddd7caf048fd96991eea (patch)
tree21eb9fddf2ac136e8168b4e03a076c3e1e2ebb2a /src/examples/subscriber
parent6a99b04fb74f6da3faea54c93d234a9b57d7bd0e (diff)
downloadpx4-firmware-1c79f0cef1f21cff7935ddd7caf048fd96991eea.tar.gz
px4-firmware-1c79f0cef1f21cff7935ddd7caf048fd96991eea.tar.bz2
px4-firmware-1c79f0cef1f21cff7935ddd7caf048fd96991eea.zip
improve param wrapper for ros, prepare for px4
Diffstat (limited to 'src/examples/subscriber')
-rw-r--r--src/examples/subscriber/subscriber.cpp12
1 files changed, 8 insertions, 4 deletions
diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp
index a8ecd4a7d..e52d661a9 100644
--- a/src/examples/subscriber/subscriber.cpp
+++ b/src/examples/subscriber/subscriber.cpp
@@ -74,13 +74,17 @@ PX4_MAIN_FUNCTION(subscriber) {
*/
px4::NodeHandle n;
- /* Define a parameter */
- PX4_PARAM_INIT("SUB_INTERV", 100);
+ /* Define parameters */
+ px4_param_t p_sub_interv = PX4_PARAM_INIT("SUB_INTERV", 100);
+ px4_param_t p_test_float = PX4_PARAM_INIT("SUB_TESTF", 3.14f);
/* Read the parameter back for testing */
int32_t sub_interval;
- PX4_PARAM_GET("SUB_INTERV", &sub_interval);
+ float test_float;
+ PX4_PARAM_GET(p_sub_interv, &sub_interval);
PX4_INFO("Param SUB_INTERV = %d", sub_interval);
+ PX4_PARAM_GET(p_test_float, &test_float);
+ PX4_INFO("Param SUB_TESTF = %f", (double)test_float);
/**
* The subscribe() call is how you tell ROS that you want to receive messages
@@ -97,7 +101,7 @@ PX4_MAIN_FUNCTION(subscriber) {
* is the number of messages that will be buffered up before beginning to throw
* away the oldest ones.
*/
- PX4_SUBSCRIBE(n, rc_channels, rc_channels_callback, 100);
+ PX4_SUBSCRIBE(n, rc_channels, rc_channels_callback, sub_interval);
PX4_SUBSCRIBE(n, rc_channels, rc_channels_callback2, 1000);
PX4_SUBSCRIBE(n, rc_channels, RCHandler::callback, rchandler, 1000);
PX4_INFO("subscribed");