Skip to content

Commit

Permalink
[fix] passing tests
Browse files Browse the repository at this point in the history
  • Loading branch information
miferco97 committed Jul 1, 2024
1 parent 44b76ee commit f6d27c4
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 25 deletions.
5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
11 changes: 5 additions & 6 deletions include/as2_platform_mavlink/mavlink_platform.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,21 +33,21 @@
*
* @author Miguel Fernández Cortizas
* Rafael Pérez Seguí
* Pedro Arias Pérez
* Javier Melero Deza
*/

#ifndef AS2_PLATFORM_MAVLINK__MAVLINK_PLATFORM_HPP_
#define AS2_PLATFORM_MAVLINK__MAVLINK_PLATFORM_HPP_

#include <Eigen/Dense>

#include <string>
#include <memory>
#include <cmath>


#include <mavros_msgs/msg/detail/attitude_target__struct.hpp>
#include <nav_msgs/msg/detail/odometry__struct.hpp>
#include <rclcpp/subscription.hpp>
#include <string>
#include <memory>

#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
Expand All @@ -56,14 +56,13 @@
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/nav_sat_fix.hpp>
#include <sensor_msgs/msg/nav_sat_status.hpp>

#include <mavros_msgs/msg/attitude_target.hpp>
#include <mavros_msgs/msg/command_code.hpp>
#include <mavros_msgs/msg/state.hpp>
#include <mavros_msgs/msg/thrust.hpp>
#include <mavros_msgs/srv/command_bool.hpp>
#include <mavros_msgs/srv/command_long.hpp>
#include <mavros_msgs/srv/set_mode.hpp>
#include <mavros_msgs/msg/attitude_target.hpp>


#include "as2_core/aerial_platform.hpp"
Expand Down
18 changes: 0 additions & 18 deletions src/mavlink_platform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,24 +93,6 @@ MavlinkPlatform::MavlinkPlatform(const rclcpp::NodeOptions & options)
std::make_shared<as2::SynchronousServiceClient<mavros_msgs::srv::SetMode>>(
"mavros/set_mode", this);


// // px4_timesync_sub_ = this->create_subscription<px4_msgs::msg::TimesyncStatus>(
// // "/fmu/out/timesync_status", rclcpp::SensorDataQoS(),
// // [this](const px4_msgs::msg::TimesyncStatus::UniquePtr msg) {
// // timestamp_.store(msg->timestamp);
// // });

// px4_gps_sub_ = this->create_subscription<px4_msgs::msg::SensorGps>(
// "/fmu/out/vehicle_gps_position", rclcpp::SensorDataQoS(),
// std::bind(&MavlinkPlatform::px4GpsCallback, this, std::placeholders::_1));

// px4_battery_sub_ = this->create_subscription<px4_msgs::msg::BatteryStatus>(
// "/fmu/out/battery_status", rclcpp::SensorDataQoS(),
// std::bind(&MavlinkPlatform::px4BatteryCallback, this, std::placeholders::_1));

// px4_odometry_sub_ = this->create_subscription<px4_msgs::msg::VehicleOdometry>(
// "/fmu/out/vehicle_odometry", rclcpp::SensorDataQoS(),
// std::bind(&MavlinkPlatform::px4odometryCallback, this, std::placeholders::_1));
tf_handler_ = std::make_shared<as2::tf::TfHandler>(this);

if (external_odom_) {
Expand Down

0 comments on commit f6d27c4

Please sign in to comment.