From f6d27c4b9405f09ae8f53d0231ba109322101441 Mon Sep 17 00:00:00 2001 From: Miguel Fernandez Cortizas Date: Mon, 1 Jul 2024 09:51:26 +0000 Subject: [PATCH] [fix] passing tests --- CMakeLists.txt | 5 ++++- .../as2_platform_mavlink/mavlink_platform.hpp | 11 +++++------ src/mavlink_platform.cpp | 18 ------------------ 3 files changed, 9 insertions(+), 25 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5afd269..442f784 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,7 +46,10 @@ set(SOURCE_CPP_FILES ) # Create the node executable -add_executable(${PROJECT_NAME}_node src/mavlink_platform_node.cpp ${SOURCE_CPP_FILES}) +add_executable(${PROJECT_NAME}_node + src/mavlink_platform_node.cpp + ${SOURCE_CPP_FILES}) + ament_target_dependencies(${PROJECT_NAME}_node ${PROJECT_DEPENDENCIES}) # Create the library diff --git a/include/as2_platform_mavlink/mavlink_platform.hpp b/include/as2_platform_mavlink/mavlink_platform.hpp index a21cc81..642a70c 100644 --- a/include/as2_platform_mavlink/mavlink_platform.hpp +++ b/include/as2_platform_mavlink/mavlink_platform.hpp @@ -33,8 +33,6 @@ * * @author Miguel Fernández Cortizas * Rafael Pérez Seguí - * Pedro Arias Pérez - * Javier Melero Deza */ #ifndef AS2_PLATFORM_MAVLINK__MAVLINK_PLATFORM_HPP_ @@ -42,12 +40,14 @@ #include +#include +#include #include + + #include #include #include -#include -#include #include #include @@ -56,14 +56,13 @@ #include #include #include - +#include #include #include #include #include #include #include -#include #include "as2_core/aerial_platform.hpp" diff --git a/src/mavlink_platform.cpp b/src/mavlink_platform.cpp index 18b31f9..ab45c37 100644 --- a/src/mavlink_platform.cpp +++ b/src/mavlink_platform.cpp @@ -93,24 +93,6 @@ MavlinkPlatform::MavlinkPlatform(const rclcpp::NodeOptions & options) std::make_shared>( "mavros/set_mode", this); - - // // px4_timesync_sub_ = this->create_subscription( - // // "/fmu/out/timesync_status", rclcpp::SensorDataQoS(), - // // [this](const px4_msgs::msg::TimesyncStatus::UniquePtr msg) { - // // timestamp_.store(msg->timestamp); - // // }); - - // px4_gps_sub_ = this->create_subscription( - // "/fmu/out/vehicle_gps_position", rclcpp::SensorDataQoS(), - // std::bind(&MavlinkPlatform::px4GpsCallback, this, std::placeholders::_1)); - - // px4_battery_sub_ = this->create_subscription( - // "/fmu/out/battery_status", rclcpp::SensorDataQoS(), - // std::bind(&MavlinkPlatform::px4BatteryCallback, this, std::placeholders::_1)); - - // px4_odometry_sub_ = this->create_subscription( - // "/fmu/out/vehicle_odometry", rclcpp::SensorDataQoS(), - // std::bind(&MavlinkPlatform::px4odometryCallback, this, std::placeholders::_1)); tf_handler_ = std::make_shared(this); if (external_odom_) {