diff --git a/mavros/CMakeLists.txt b/mavros/CMakeLists.txt index fb35502d8..0a311bd1c 100644 --- a/mavros/CMakeLists.txt +++ b/mavros/CMakeLists.txt @@ -20,6 +20,8 @@ set(CMAKE_CXX_EXTENSIONS ON) find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) +find_package(PythonLibs REQUIRED) + # find mavros dependencies find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) @@ -67,6 +69,7 @@ include_directories( ${mavlink_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ${GeographicLib_INCLUDE_DIRS} + ${PYTHON_INCLUDE_DIRS} ) ## Check if the datasets are installed diff --git a/mavros/src/plugins/rc_io.cpp b/mavros/src/plugins/rc_io.cpp index 3f3e3ac6b..b91d887d9 100644 --- a/mavros/src/plugins/rc_io.cpp +++ b/mavros/src/plugins/rc_io.cpp @@ -127,20 +127,17 @@ class RCIOPlugin : public plugin::Plugin RCLCPP_INFO_EXPRESSION( get_logger(), !has_rc_channels_msg.exchange( true), "RC_CHANNELS message detected!"); - + if (channels.chancount > MAX_CHANCNT) { RCLCPP_WARN_THROTTLE( get_logger(), *get_clock(), 60000, "FCU receives %u RC channels, but RC_CHANNELS can store %zu", channels.chancount, MAX_CHANCNT); - - channels.chancount = MAX_CHANCNT; } - - raw_rc_in.resize(channels.chancount); + raw_rc_in.resize(MAX_CHANCNT); // switch works as start point selector. - switch (channels.chancount) { + switch (MAX_CHANCNT) { // [[[cog: // for i in range(18, 0, -1): // cog.outl(f"case {i}: raw_rc_in[{i - 1}] = channels.chan{i}_raw; [[fallthrough]];") diff --git a/mavros_extras/CMakeLists.txt b/mavros_extras/CMakeLists.txt index 63591185c..351831164 100644 --- a/mavros_extras/CMakeLists.txt +++ b/mavros_extras/CMakeLists.txt @@ -18,6 +18,7 @@ set(CMAKE_C_EXTENSIONS ON) set(CMAKE_CXX_EXTENSIONS ON) find_package(ament_cmake REQUIRED) +find_package(PythonLibs REQUIRED) # find mavros dependencies find_package(rclcpp REQUIRED) @@ -68,6 +69,7 @@ include_directories( ${mavlink_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ${GeographicLib_INCLUDE_DIRS} + ${PYTHON_INCLUDE_DIRS} ) if(rclcpp_VERSION VERSION_LESS 9.0.0)