mavlink: Comment out px4 drivers in nuttx protected build

These link directly to cdev, and thus cannot be linked into user-side module.

There should be simple implementation for these which work purely on uORB; without
fixing this the HITL won't work in protected build.

Also link to nuttx_apps in nuttx net build for netlib dependency

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This commit is contained in:
Jukka Laitinen
2020-12-08 08:37:32 +02:00
parent 7ccdaeb4f5
commit e40b29a6d8
3 changed files with 26 additions and 7 deletions
+15 -4
View File
@@ -66,10 +66,6 @@ px4_add_module(
DEPENDS
airspeed
component_general_json # for checksums.h
drivers_accelerometer
drivers_barometer
drivers_gyroscope
drivers_magnetometer
git_mavlink_v2
conversion
geo
@@ -80,3 +76,18 @@ px4_add_module(
if(PX4_TESTING)
add_subdirectory(mavlink_tests)
endif()
if (NOT ${PX4_PLATFORM} STREQUAL "nuttx" OR CONFIG_BUILD_FLAT)
target_link_libraries(modules__mavlink
PRIVATE
drivers_accelerometer
drivers_barometer
drivers_gyroscope
drivers_magnetometer
)
endif()
if(${PX4_PLATFORM} STREQUAL "nuttx" AND CONFIG_NET)
# netlib_get_ipv4addr
target_link_libraries(modules__mavlink PRIVATE nuttx_apps)
endif()
+7 -2
View File
@@ -73,10 +73,12 @@
MavlinkReceiver::~MavlinkReceiver()
{
delete _tune_publisher;
#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT)
delete _px4_accel;
delete _px4_baro;
delete _px4_gyro;
delete _px4_mag;
#endif
}
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
@@ -2223,6 +2225,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
const uint64_t timestamp = hrt_absolute_time();
#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT)
// temperature only updated with baro
float temperature = NAN;
@@ -2291,6 +2294,8 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
}
}
#endif
// differential pressure
if ((hil_sensor.fields_updated & SensorSource::DIFF_PRESS) == SensorSource::DIFF_PRESS) {
differential_pressure_s report{};
@@ -2697,7 +2702,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
hil_local_pos.timestamp = hrt_absolute_time();
_local_pos_pub.publish(hil_local_pos);
}
#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT)
/* accelerometer */
{
if (_px4_accel == nullptr) {
@@ -2731,7 +2736,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
_px4_gyro->update(timestamp_sample, hil_state.rollspeed, hil_state.pitchspeed, hil_state.yawspeed);
}
}
#endif
/* battery status */
{
battery_status_s hil_battery_status{};
+4 -1
View File
@@ -340,10 +340,13 @@ private:
BARO = 0b1101000000000,
DIFF_PRESS = 0b10000000000
};
PX4Accelerometer *_px4_accel{nullptr};
#if !defined(__PX4_NUTTX) || defined(CONFIG_BUILD_FLAT)
PX4Accelerometer *_px4_accel {nullptr};
PX4Barometer *_px4_baro{nullptr};
PX4Gyroscope *_px4_gyro{nullptr};
PX4Magnetometer *_px4_mag{nullptr};
#endif
static constexpr unsigned int MOM_SWITCH_COUNT{8};
uint8_t _mom_switch_pos[MOM_SWITCH_COUNT] {};