Browse Source

delete obsolete examples/subscriber

sbg
Daniel Agar 6 years ago
parent
commit
67e5986c9b
  1. 1
      boards/airmind/mindpx-v2/default.cmake
  2. 1
      boards/atmel/same70xplained/default.cmake
  3. 1
      boards/auav/x21/default.cmake
  4. 1
      boards/av/x-v1/default.cmake
  5. 1
      boards/gumstix/aerocore2/default.cmake
  6. 1
      boards/intel/aerofc-v1/default.cmake
  7. 1
      boards/intel/aerofc-v1/rtps.cmake
  8. 1
      boards/nxp/fmuk66-v3/default.cmake
  9. 1
      boards/omnibus/f4sd/default.cmake
  10. 1
      boards/px4/fmu-v3/default.cmake
  11. 1
      boards/px4/fmu-v3/rtps.cmake
  12. 1
      boards/px4/fmu-v3/stackcheck.cmake
  13. 1
      boards/px4/fmu-v4/default.cmake
  14. 1
      boards/px4/fmu-v4/rtps.cmake
  15. 1
      boards/px4/fmu-v4/stackcheck.cmake
  16. 1
      boards/px4/fmu-v4pro/default.cmake
  17. 1
      boards/px4/fmu-v4pro/rtps.cmake
  18. 1
      boards/px4/fmu-v5/default.cmake
  19. 1
      boards/px4/fmu-v5/rtps.cmake
  20. 1
      boards/px4/fmu-v5/stackcheck.cmake
  21. 1
      boards/stm/32f4discovery/default.cmake
  22. 1
      boards/stm/nucleo-F767ZI/default.cmake
  23. 43
      src/examples/subscriber/CMakeLists.txt
  24. 107
      src/examples/subscriber/subscriber_example.cpp
  25. 67
      src/examples/subscriber/subscriber_example.h
  26. 55
      src/examples/subscriber/subscriber_main.cpp
  27. 57
      src/examples/subscriber/subscriber_params.c
  28. 43
      src/examples/subscriber/subscriber_params.h
  29. 98
      src/examples/subscriber/subscriber_start_nuttx.cpp

1
boards/airmind/mindpx-v2/default.cmake

@ -109,7 +109,6 @@ px4_add_board( @@ -109,7 +109,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/atmel/same70xplained/default.cmake

@ -109,7 +109,6 @@ px4_add_board( @@ -109,7 +109,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/auav/x21/default.cmake

@ -114,7 +114,6 @@ px4_add_board( @@ -114,7 +114,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/av/x-v1/default.cmake

@ -114,7 +114,6 @@ px4_add_board( @@ -114,7 +114,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/gumstix/aerocore2/default.cmake

@ -110,7 +110,6 @@ px4_add_board( @@ -110,7 +110,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/intel/aerofc-v1/default.cmake

@ -92,7 +92,6 @@ px4_add_board( @@ -92,7 +92,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/intel/aerofc-v1/rtps.cmake

@ -95,7 +95,6 @@ px4_add_board( @@ -95,7 +95,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/nxp/fmuk66-v3/default.cmake

@ -110,7 +110,6 @@ px4_add_board( @@ -110,7 +110,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/omnibus/f4sd/default.cmake

@ -104,7 +104,6 @@ px4_add_board( @@ -104,7 +104,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/px4/fmu-v3/default.cmake

@ -122,7 +122,6 @@ px4_add_board( @@ -122,7 +122,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v3/rtps.cmake

@ -123,7 +123,6 @@ px4_add_board( @@ -123,7 +123,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v3/stackcheck.cmake

@ -122,7 +122,6 @@ px4_add_board( @@ -122,7 +122,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/px4/fmu-v4/default.cmake

@ -107,7 +107,6 @@ px4_add_board( @@ -107,7 +107,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v4/rtps.cmake

@ -109,7 +109,6 @@ px4_add_board( @@ -109,7 +109,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v4/stackcheck.cmake

@ -107,7 +107,6 @@ px4_add_board( @@ -107,7 +107,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/px4/fmu-v4pro/default.cmake

@ -121,7 +121,6 @@ px4_add_board( @@ -121,7 +121,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v4pro/rtps.cmake

@ -122,7 +122,6 @@ px4_add_board( @@ -122,7 +122,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v5/default.cmake

@ -121,7 +121,6 @@ px4_add_board( @@ -121,7 +121,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v5/rtps.cmake

@ -123,7 +123,6 @@ px4_add_board( @@ -123,7 +123,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/px4/fmu-v5/stackcheck.cmake

@ -122,7 +122,6 @@ px4_add_board( @@ -122,7 +122,6 @@ px4_add_board(
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
#rover_steering_control # Rover example app
#segway
#subscriber
#uuv_example_app
)

1
boards/stm/32f4discovery/default.cmake

@ -99,7 +99,6 @@ px4_add_board( @@ -99,7 +99,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

1
boards/stm/nucleo-F767ZI/default.cmake

@ -108,7 +108,6 @@ px4_add_board( @@ -108,7 +108,6 @@ px4_add_board(
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
#subscriber
uuv_example_app
)

43
src/examples/subscriber/CMakeLists.txt

@ -1,43 +0,0 @@ @@ -1,43 +0,0 @@
############################################################################
#
# Copyright (c) 2015 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.
#
############################################################################
px4_add_module(
MODULE examples__subscriber
MAIN subscriber
STACK_MAIN 2400
SRCS
subscriber_main.cpp
subscriber_start_nuttx.cpp
subscriber_example.cpp
subscriber_params.c
DEPENDS
)

107
src/examples/subscriber/subscriber_example.cpp

@ -1,107 +0,0 @@ @@ -1,107 +0,0 @@
/****************************************************************************
*
* 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 subscriber_example.cpp
* Example subscriber for ros and px4
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "subscriber_params.h"
#include "subscriber_example.h"
using namespace px4;
void rc_channels_callback_function(const px4_rc_channels &msg)
{
PX4_INFO("I heard: [%" PRIu64 "]", msg.data().timestamp_last_valid);
}
SubscriberExample::SubscriberExample() :
_n(_appState),
_p_sub_interv("SUB_INTERV", PARAM_SUB_INTERV_DEFAULT),
_p_test_float("SUB_TESTF", PARAM_SUB_TESTF_DEFAULT)
{
/* Read the parameter back as example */
_p_sub_interv.update();
_p_test_float.update();
PX4_INFO("Param SUB_INTERV = %d", _p_sub_interv.get());
PX4_INFO("Param SUB_TESTF = %.3f", (double)_p_test_float.get());
/* Do some subscriptions */
/* Function */
_n.subscribe<px4_rc_channels>(rc_channels_callback_function, _p_sub_interv.get());
/* No callback */
_sub_rc_chan = _n.subscribe<px4_rc_channels>(500);
/* Class method */
_n.subscribe<px4_rc_channels>(&SubscriberExample::rc_channels_callback, this, 1000);
/* Another class method */
_n.subscribe<px4_vehicle_attitude>(&SubscriberExample::vehicle_attitude_callback, this, 1000);
/* Yet antoher class method */
_n.subscribe<px4_parameter_update>(&SubscriberExample::parameter_update_callback, this, 1000);
PX4_INFO("subscribed");
}
/**
* This tutorial demonstrates simple receipt of messages over the PX4 middleware system.
* Also the current value of the _sub_rc_chan subscription is printed
*/
void SubscriberExample::rc_channels_callback(const px4_rc_channels &msg)
{
PX4_INFO("rc_channels_callback (method): [%" PRIu64 "]",
msg.data().timestamp_last_valid);
PX4_INFO("rc_channels_callback (method): value of _sub_rc_chan: [%" PRIu64 "]",
_sub_rc_chan->data().timestamp_last_valid);
}
void SubscriberExample::vehicle_attitude_callback(const px4_vehicle_attitude &msg)
{
PX4_INFO("vehicle_attitude_callback (method): [%" PRIu64 "]",
msg.data().timestamp);
}
void SubscriberExample::parameter_update_callback(const px4_parameter_update &msg)
{
PX4_INFO("parameter_update_callback (method): [%" PRIu64 "]",
msg.data().timestamp);
_p_sub_interv.update();
PX4_INFO("Param SUB_INTERV = %d", _p_sub_interv.get());
_p_test_float.update();
PX4_INFO("Param SUB_TESTF = %.3f", (double)_p_test_float.get());
}

67
src/examples/subscriber/subscriber_example.h

@ -1,67 +0,0 @@ @@ -1,67 +0,0 @@
/****************************************************************************
*
* 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 subscriber_example.h
* Example subscriber for ros and px4
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <px4.h>
using namespace px4;
void rc_channels_callback_function(const px4_rc_channels &msg);
class SubscriberExample
{
public:
SubscriberExample();
~SubscriberExample() {}
void spin() {_n.spin();}
protected:
px4::NodeHandle _n;
px4::ParameterInt _p_sub_interv;
px4::ParameterFloat _p_test_float;
px4::Subscriber<px4_rc_channels> *_sub_rc_chan;
AppState _appState;
void rc_channels_callback(const px4_rc_channels &msg);
void vehicle_attitude_callback(const px4_vehicle_attitude &msg);
void parameter_update_callback(const px4_parameter_update &msg);
};

55
src/examples/subscriber/subscriber_main.cpp

@ -1,55 +0,0 @@ @@ -1,55 +0,0 @@
/****************************************************************************
*
* 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 subscriber_main.cpp
* Example subscriber for ros and px4
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "subscriber_example.h"
bool thread_running = false; /**< Deamon status flag */
int main(int argc, char **argv)
{
px4::init(argc, argv, "subscriber");
PX4_INFO("starting");
SubscriberExample s;
thread_running = true;
s.spin();
PX4_INFO("exiting.");
thread_running = false;
return 0;
}

57
src/examples/subscriber/subscriber_params.c

@ -1,57 +0,0 @@ @@ -1,57 +0,0 @@
/****************************************************************************
*
* 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
* 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 subscriber_params.c
* Parameters for the subscriber example
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <px4_defines.h>
#include "subscriber_params.h"
/**
* Interval of one subscriber in the example in ms
*
* @unit ms
* @group Subscriber Example
*/
PX4_PARAM_DEFINE_INT32(SUB_INTERV);
/**
* Float Demonstration Parameter in the Example
*
* @group Subscriber Example
*/
PX4_PARAM_DEFINE_FLOAT(SUB_TESTF);

43
src/examples/subscriber/subscriber_params.h

@ -1,43 +0,0 @@ @@ -1,43 +0,0 @@
/****************************************************************************
*
* 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
* 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 subscriber_params.h
* Default parameters for the subscriber example
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#define PARAM_SUB_INTERV_DEFAULT 100
#define PARAM_SUB_TESTF_DEFAULT 3.14f

98
src/examples/subscriber/subscriber_start_nuttx.cpp

@ -1,98 +0,0 @@ @@ -1,98 +0,0 @@
/****************************************************************************
*
* 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 subscriber_start_nuttx.cpp
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
extern bool thread_running;
int daemon_task; /**< Handle of deamon task / thread */
namespace px4
{
bool task_should_exit = false;
}
using namespace px4;
extern int main(int argc, char **argv);
extern "C" __EXPORT int subscriber_main(int argc, char *argv[]);
int subscriber_main(int argc, char *argv[])
{
if (argc < 2) {
errx(1, "usage: subscriber {start|stop|status}");
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("already running");
/* this is not an error */
exit(0);
}
task_should_exit = false;
daemon_task = px4_task_spawn_cmd("subscriber",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
main,
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
exit(0);
}
if (!strcmp(argv[1], "stop")) {
task_should_exit = true;
exit(0);
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
warnx("is running");
} else {
warnx("not started");
}
exit(0);
}
warnx("unrecognized command");
return 1;
}
Loading…
Cancel
Save