aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.gitignore1
-rw-r--r--CMakeLists.txt1
-rw-r--r--src/drivers/px4io/px4io.cpp5
-rw-r--r--src/examples/publisher/publisher.cpp5
-rw-r--r--src/examples/subscriber/subscriber.cpp5
-rw-r--r--src/include/containers/List.hpp1
-rw-r--r--src/include/px4.h7
-rw-r--r--src/modules/commander/commander.cpp5
-rw-r--r--src/modules/commander/state_machine_helper.cpp2
-rw-r--r--src/modules/px4iofirmware/mixer.cpp20
-rw-r--r--src/modules/px4iofirmware/registers.c21
-rw-r--r--src/modules/sdlog2/sdlog2.c7
-rw-r--r--src/modules/uORB/Publication.cpp1
-rw-r--r--src/modules/uORB/Subscription.cpp1
-rw-r--r--src/modules/uORB/topics/vehicle_status.h1
-rw-r--r--src/platforms/nuttx/px4_nodehandle.cpp39
-rw-r--r--src/platforms/px4_nodehandle.h75
-rw-r--r--src/platforms/px4_publisher.h31
-rw-r--r--src/platforms/px4_subscriber.h32
-rw-r--r--src/platforms/ros/px4_nodehandle.cpp44
-rw-r--r--src/platforms/ros/px4_publisher.cpp1
-rw-r--r--src/platforms/ros/px4_subscriber.cpp1
22 files changed, 279 insertions, 27 deletions
diff --git a/.gitignore b/.gitignore
index 8b09e4783..69112ee1f 100644
--- a/.gitignore
+++ b/.gitignore
@@ -17,6 +17,7 @@
.~lock.*
Archives/*
Build/*
+build/*
core
cscope.out
Firmware.sublime-workspace
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 36c2ffeff..8eb81c92c 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -104,6 +104,7 @@ add_library(px4
src/platforms/ros/px4_ros_impl.cpp
src/platforms/ros/px4_publisher.cpp
src/platforms/ros/px4_subscriber.cpp
+ src/platforms/ros/px4_nodehandle.cpp
)
target_link_libraries(px4
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 519ba663a..6f02ba62c 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -817,6 +817,11 @@ PX4IO::init()
}
+ /* set safety to off if circuit breaker enabled */
+ if (circuit_breaker_enabled("CBRK_IO_SAFETY", CBRK_IO_SAFETY_KEY)) {
+ (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
+ }
+
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
diff --git a/src/examples/publisher/publisher.cpp b/src/examples/publisher/publisher.cpp
index 91e063162..c09cca1fc 100644
--- a/src/examples/publisher/publisher.cpp
+++ b/src/examples/publisher/publisher.cpp
@@ -38,7 +38,7 @@ int main(int argc, char **argv)
px4::init(argc, argv, "px4_publisher");
- ros::NodeHandle n;
+ px4::NodeHandle n;
/**
* The advertise() function is how you tell ROS that you want to
@@ -57,7 +57,8 @@ int main(int argc, char **argv)
* than we can send them, the number here specifies how many messages to
* buffer up before throwing some away.
*/
- ros::Publisher rc_channels_pub = n.advertise<px4::rc_channels>("rc_channels", 1000);
+ px4::Publisher rc_channels_pub = n.advertise<px4::rc_channels>(PX4_TOPIC(rc_channels));
+
px4::Rate loop_rate(10);
diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp
index bf16bf84e..b91859027 100644
--- a/src/examples/subscriber/subscriber.cpp
+++ b/src/examples/subscriber/subscriber.cpp
@@ -57,7 +57,7 @@ int main(int argc, char **argv)
* The first NodeHandle constructed will fully initialize this node, and the last
* NodeHandle destructed will close down the node.
*/
- ros::NodeHandle n;
+ px4::NodeHandle n;
/**
* The subscribe() call is how you tell ROS that you want to receive messages
@@ -74,7 +74,8 @@ int main(int argc, char **argv)
* is the number of messages that will be buffered up before beginning to throw
* away the oldest ones.
*/
- ros::Subscriber sub = n.subscribe("rc_channels", 1000, rc_channels_callback);
+ px4::Subscriber sub = n.subscribe(PX4_TOPIC(rc_channels), rc_channels_callback);
+ PX4_INFO("subscribed");
/**
* px4::spin() will enter a loop, pumping callbacks. With this version, all
diff --git a/src/include/containers/List.hpp b/src/include/containers/List.hpp
index 13cbda938..5c0ba59fd 100644
--- a/src/include/containers/List.hpp
+++ b/src/include/containers/List.hpp
@@ -38,6 +38,7 @@
*/
#pragma once
+#include <cstddef>
template<class T>
class __EXPORT ListNode
diff --git a/src/include/px4.h b/src/include/px4.h
index 0aba2ee77..391972b12 100644
--- a/src/include/px4.h
+++ b/src/include/px4.h
@@ -46,15 +46,22 @@
* Building for running within the ROS environment
*/
#include "ros/ros.h"
+
#define PX4_WARN ROS_WARN
#define PX4_INFO ROS_INFO
+#define PX4_TOPIC(name) #name
#else
/*
* Building for NuttX
*/
+#include <uORB/uORB.h>
+
#define PX4_WARN warnx
#define PX4_INFO warnx
+#define PX4_TOPIC(name) ORB_ID(name)
#endif
#include "../platforms/px4_defines.h"
#include "../platforms/px4_middleware.h"
+#include "../platforms/px4_nodehandle.h"
+#include "../platforms/px4_subscriber.h"
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index e081955d0..c9c8d16b5 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1548,7 +1548,7 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RC signal regained");
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums",(hrt_absolute_time()-status.rc_signal_lost_timestamp)/1000);
status_changed = true;
}
}
@@ -1649,8 +1649,9 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (!status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST");
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST (at t=%llums)",hrt_absolute_time()/1000);
status.rc_signal_lost = true;
+ status.rc_signal_lost_timestamp=sp_man.timestamp;
status_changed = true;
}
}
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index e37019d02..465f9cdc5 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -706,7 +706,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
}
if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) {
- mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION MISSING");
+ mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION ISSUE");
// XXX do not make this fatal yet
}
}
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index c0b8ac358..66f0969de 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -353,12 +353,16 @@ static unsigned mixer_text_length = 0;
int
mixer_handle_text(const void *buffer, size_t length)
{
- /* do not allow a mixer change while safety off */
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
+ /* do not allow a mixer change while safety off and FMU armed */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
+ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
return 1;
}
- /* abort if we're in the mixer */
+ /* disable mixing, will be enabled once load is complete */
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_MIXER_OK);
+
+ /* abort if we're in the mixer - the caller is expected to retry */
if (in_mixer) {
return 1;
}
@@ -367,17 +371,16 @@ mixer_handle_text(const void *buffer, size_t length)
isr_debug(2, "mix txt %u", length);
- if (length < sizeof(px4io_mixdata))
+ if (length < sizeof(px4io_mixdata)) {
return 0;
+ }
- unsigned text_length = length - sizeof(px4io_mixdata);
+ unsigned text_length = length - sizeof(px4io_mixdata);
switch (msg->action) {
case F2I_MIXER_ACTION_RESET:
isr_debug(2, "reset");
- /* FIRST mark the mixer as invalid */
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
/* THEN actually delete it */
mixer_group.reset();
mixer_text_length = 0;
@@ -386,9 +389,6 @@ mixer_handle_text(const void *buffer, size_t length)
case F2I_MIXER_ACTION_APPEND:
isr_debug(2, "append %d", length);
- /* disable mixing during the update */
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
-
/* check for overflow - this would be really fatal */
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index fbfdd35db..a1a02965f 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -407,10 +407,11 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
/* handle text going to the mixer parser */
case PX4IO_PAGE_MIXERLOAD:
- if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
- (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
- return mixer_handle_text(values, num_values * sizeof(*values));
- }
+ /* do not change the mixer if FMU is armed and IO's safety is off
+ * this state defines an active system. This check is done in the
+ * text handling function.
+ */
+ return mixer_handle_text(values, num_values * sizeof(*values));
break;
default:
@@ -583,8 +584,10 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_REBOOT_BL:
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
- (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
+ // do not reboot if FMU is armed and IO's safety is off
+ // this state defines an active system.
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
+ (r_status_flags & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
// don't allow reboot while armed
break;
}
@@ -631,9 +634,11 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
/**
* do not allow a RC config change while outputs armed
+ * = FMU is armed and IO's safety is off
+ * this state defines an active system.
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
- (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
+ (r_status_flags & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
break;
}
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index af580f1f7..8638a4904 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -496,6 +496,8 @@ static void *logwriter_thread(void *arg)
/* set name */
prctl(PR_SET_NAME, "sdlog2_writer", 0);
+ perf_counter_t perf_write = perf_alloc(PC_ELAPSED, "sd write");
+
int log_fd = open_log_file();
if (log_fd < 0) {
@@ -553,7 +555,9 @@ static void *logwriter_thread(void *arg)
n = available;
}
+ perf_begin(perf_write);
n = write(log_fd, read_ptr, n);
+ perf_end(perf_write);
should_wait = (n == available) && !is_part;
@@ -586,6 +590,9 @@ static void *logwriter_thread(void *arg)
fsync(log_fd);
close(log_fd);
+ /* free performance counter */
+ perf_free(perf_write);
+
return NULL;
}
diff --git a/src/modules/uORB/Publication.cpp b/src/modules/uORB/Publication.cpp
index fd5c511ef..12ef83aa0 100644
--- a/src/modules/uORB/Publication.cpp
+++ b/src/modules/uORB/Publication.cpp
@@ -78,5 +78,6 @@ template class __EXPORT Publication<vehicle_rates_setpoint_s>;
template class __EXPORT Publication<actuator_outputs_s>;
template class __EXPORT Publication<encoders_s>;
template class __EXPORT Publication<tecs_status_s>;
+template class __EXPORT Publication<rc_channels_s>;
}
diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp
index 69969307e..a681ccb30 100644
--- a/src/modules/uORB/Subscription.cpp
+++ b/src/modules/uORB/Subscription.cpp
@@ -93,5 +93,6 @@ template class __EXPORT Subscription<vehicle_local_position_setpoint_s>;
template class __EXPORT Subscription<vehicle_local_position_s>;
template class __EXPORT Subscription<vehicle_attitude_setpoint_s>;
template class __EXPORT Subscription<vehicle_rates_setpoint_s>;
+template class __EXPORT Subscription<rc_channels_s>;
} // namespace uORB
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 91491c148..8ec9d98d6 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -201,6 +201,7 @@ struct vehicle_status_s {
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception lost */
+ uint64_t rc_signal_lost_timestamp; /**< Time at which the RC reception was lost */
bool rc_signal_lost_cmd; /**< true if RC lost mode is commanded */
bool rc_input_blocked; /**< set if RC input should be ignored */
diff --git a/src/platforms/nuttx/px4_nodehandle.cpp b/src/platforms/nuttx/px4_nodehandle.cpp
new file mode 100644
index 000000000..9d43daa49
--- /dev/null
+++ b/src/platforms/nuttx/px4_nodehandle.cpp
@@ -0,0 +1,39 @@
+/****************************************************************************
+ *
+ * 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 px4_nodehandle.cpp
+ *
+ * PX4 Middleware Wrapper Nodehandle
+ */
+#include <px4_nodehandle.h>
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h
index d278828b7..fa2c8d6a4 100644
--- a/src/platforms/px4_nodehandle.h
+++ b/src/platforms/px4_nodehandle.h
@@ -36,11 +36,86 @@
*
* PX4 Middleware Wrapper Node Handle
*/
+#pragma once
+
+/* includes for all platforms */
+#include <px4_subscriber.h>
+#include <px4_publisher.h>
+
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+/* includes when building for ros */
+#include "ros/ros.h"
+#include <list>
+#include <inttypes.h>
+#else
+/* includes when building for NuttX */
+#include <containers/List.hpp>
+#endif
namespace px4
{
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+class NodeHandle :
+ private ros::NodeHandle
+{
+public:
+ NodeHandle() :
+ ros::NodeHandle(),
+ _subs(),
+ _pubs()
+ {}
+
+ ~NodeHandle() {
+ //XXX empty lists
+ };
+
+ template<typename M>
+ Subscriber subscribe(const char *topic, void(*fp)(M)) {
+ ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, fp);
+ Subscriber sub(ros_sub);
+ _subs.push_back(sub);
+ return sub;
+ }
+
+ template<typename M>
+ Publisher advertise(const char *topic) {
+ ros::Publisher ros_pub = ros::NodeHandle::advertise<M>(topic, kQueueSizeDefault);
+ Publisher pub(ros_pub);
+ _pubs.push_back(pub);
+ return pub;
+ }
+private:
+ static const uint32_t kQueueSizeDefault = 1000;
+ std::list<Subscriber> _subs;
+ std::list<Publisher> _pubs;
+};
+#else
class NodeHandle
{
+public:
+ NodeHandle() :
+ _subs(),
+ _pubs()
+ {}
+
+ ~NodeHandle() {};
+
+ template<typename M>
+ Subscriber subscribe(const char *topic, void(*fp)(M)) {
+ Subscriber sub(&_subs, , interval);
+ return sub;
+ }
+
+ template<typename M>
+ Publisher advertise(const char *topic) {
+ Publisher pub(ros_pub);
+ _pubs.push_back(pub);
+ return pub;
+ }
+private:
+ List<Subscriber> _subs;
+ List<Publisher> _pubs;
};
+#endif
}
diff --git a/src/platforms/px4_publisher.h b/src/platforms/px4_publisher.h
index 1b0952155..53e63b695 100644
--- a/src/platforms/px4_publisher.h
+++ b/src/platforms/px4_publisher.h
@@ -36,11 +36,40 @@
*
* PX4 Middleware Wrapper Node Handle
*/
+#pragma once
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+/* includes when building for ros */
+#include "ros/ros.h"
+#else
+/* includes when building for NuttX */
+#include <uORB/Publication.hpp>
+#endif
namespace px4
{
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
class Publisher
{
-
+public:
+ Publisher(ros::Publisher ros_pub) : _ros_pub(ros_pub)
+ {}
+ ~Publisher() {};
+ template<typename M>
+ int publish(const M &msg) { _ros_pub.publish(msg); return 0; }
+private:
+ ros::Publisher _ros_pub;
+};
+#else
+template<typename M>
+class Publisher :
+ public uORB::Publication<M>
+public:
+ Publisher(List<SubscriptionBase *> * list,
+ const struct orb_metadata *meta, unsigned interval) :
+ uORB::Publication(list, meta)
+ {}
+ ~Publisher() {};
+{
};
+#endif
}
diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h
index 8759f8b05..6312e0cbe 100644
--- a/src/platforms/px4_subscriber.h
+++ b/src/platforms/px4_subscriber.h
@@ -36,11 +36,41 @@
*
* PX4 Middleware Wrapper Subscriber
*/
+#pragma once
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+/* includes when building for ros */
+#include "ros/ros.h"
+#else
+/* includes when building for NuttX */
+#include <uORB/Subscription.hpp>
+#endif
namespace px4
{
+
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
class Subscriber
{
-
+public:
+ Subscriber(ros::Subscriber ros_sub) :
+ _ros_sub(ros_sub)
+ {}
+ ~Subscriber() {};
+private:
+ ros::Subscriber _ros_sub;
};
+#else
+template<typename M>
+class Subscriber :
+ public uORB::Subscription<M>
+public:
+ Subscriber(List<SubscriptionBase *> * list,
+ const struct orb_metadata *meta, unsigned interval) :
+ uORB::Subsciption(list, meta, interval)
+ {}
+ ~Subscriber() {};
+{
+};
+#endif
+
}
diff --git a/src/platforms/ros/px4_nodehandle.cpp b/src/platforms/ros/px4_nodehandle.cpp
new file mode 100644
index 000000000..6ac3c76d3
--- /dev/null
+++ b/src/platforms/ros/px4_nodehandle.cpp
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * 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 px4_nodehandle.cpp
+ *
+ * PX4 Middleware Wrapper Nodehandle
+ */
+#include <px4_nodehandle.h>
+
+namespace px4
+{
+}
+
diff --git a/src/platforms/ros/px4_publisher.cpp b/src/platforms/ros/px4_publisher.cpp
index ab6035b22..f02dbe4c9 100644
--- a/src/platforms/ros/px4_publisher.cpp
+++ b/src/platforms/ros/px4_publisher.cpp
@@ -36,5 +36,6 @@
*
* PX4 Middleware Wrapper for Publisher
*/
+#include <px4_publisher.h>
diff --git a/src/platforms/ros/px4_subscriber.cpp b/src/platforms/ros/px4_subscriber.cpp
index 088c08fdb..d040b860d 100644
--- a/src/platforms/ros/px4_subscriber.cpp
+++ b/src/platforms/ros/px4_subscriber.cpp
@@ -37,4 +37,5 @@
* PX4 Middleware Wrapper Subscriber
*/
+#include <px4_subscriber.h>