Skip to content

Commit

Permalink
Merge pull request #317 from aerostack2/316-tf2_geometry_msgs-dep
Browse files Browse the repository at this point in the history
Only use tf2_geometry_msgs library when needed
  • Loading branch information
miferco97 committed Aug 22, 2023
2 parents 733dd6e + 1ba45fc commit ece064c
Show file tree
Hide file tree
Showing 18 changed files with 3 additions and 19 deletions.
Expand Up @@ -9,7 +9,6 @@
#include "dji_flight_controller.hpp"
#include "dji_subscriber.hpp"
#include "dji_telemetry.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

DJIMatricePlatform::DJIMatricePlatform(int argc, char** argv)
: as2::AerialPlatform() {
Expand Down
1 change: 0 additions & 1 deletion as2_behaviors/as2_behaviors_motion/CMakeLists.txt
Expand Up @@ -25,7 +25,6 @@ set(PROJECT_DEPENDENCIES
as2_behavior
as2_motion_reference_handlers
geometry_msgs
tf2_geometry_msgs
Eigen3
)

Expand Down
1 change: 0 additions & 1 deletion as2_core/include/as2_core/utils/frame_utils.hpp
Expand Up @@ -36,7 +36,6 @@

#include <math.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <Eigen/Geometry>
#include <geometry_msgs/msg/quaternion.hpp>

Expand Down
5 changes: 2 additions & 3 deletions as2_core/include/as2_core/utils/tf_utils.hpp
Expand Up @@ -33,17 +33,16 @@
#ifndef TF_UTILS_HPP_
#define TF_UTILS_HPP_

#include <tf2/convert.h>
#include <tf2/time.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <chrono>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/vector3_stamped.hpp>
#include <nav_msgs/msg/path.hpp>

#include <tf2/convert.h>
#include <chrono>
#include "as2_core/node.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
Expand Down
1 change: 1 addition & 0 deletions as2_core/package.xml
Expand Up @@ -26,6 +26,7 @@

<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>
<depend>image_transport</depend>
<depend>cv_bridge</depend>

Expand Down
Expand Up @@ -21,7 +21,6 @@ set(PROJECT_DEPENDENCIES
realsense2
tf2
tf2_ros
tf2_geometry_msgs
)

foreach(dependency ${PROJECT_DEPENDENCIES})
Expand Down
Expand Up @@ -38,7 +38,6 @@
#include "as2_core/sensor.hpp"
#include "as2_core/utils/tf_utils.hpp"

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/static_transform_broadcaster.h>
#include <librealsense2/rs.hpp>

Expand Down
1 change: 0 additions & 1 deletion as2_hardware_drivers/as2_realsense_interface/package.xml
Expand Up @@ -22,7 +22,6 @@
<depend>librealsense2</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
1 change: 0 additions & 1 deletion as2_motion_controller/CMakeLists.txt
Expand Up @@ -27,7 +27,6 @@ set(PROJECT_DEPENDENCIES
as2_msgs
as2_motion_reference_handlers
geometry_msgs
tf2_geometry_msgs
Eigen3
benchmark
)
Expand Down
1 change: 0 additions & 1 deletion as2_motion_controller/package.xml
Expand Up @@ -19,7 +19,6 @@
<depend>as2_msgs</depend>
<depend>as2_motion_reference_handlers</depend>
<depend>geometry_msgs</depend>
<depend>tf2_geometry_msgs</depend>
<depend>eigen</depend>
<depend>benchmark</depend>

Expand Down
Expand Up @@ -50,7 +50,6 @@
#include "as2_msgs/msg/trajectory_point.hpp"

#include <Eigen/src/Core/GlobalFunctions.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

namespace differential_flatness_controller {
struct UAV_state {
Expand Down
Expand Up @@ -12,7 +12,6 @@

using namespace std::chrono_literals;

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <pid_controller/PID_3D.hpp>
#include <vector>

Expand Down
Expand Up @@ -51,7 +51,6 @@
#include "pid_controller/PID.hpp"
#include "pid_controller/PID_3D.hpp"

#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>

Expand Down
Expand Up @@ -45,7 +45,6 @@

#include "as2_core/node.hpp"
#include "basic_motion_references.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

namespace as2 {
namespace motionReferenceHandlers {
Expand Down
Expand Up @@ -46,7 +46,6 @@

#include "as2_core/node.hpp"
#include "basic_motion_references.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

namespace as2 {
namespace motionReferenceHandlers {
Expand Down
Expand Up @@ -46,7 +46,6 @@

#include "as2_core/node.hpp"
#include "basic_motion_references.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

namespace as2 {
namespace motionReferenceHandlers {
Expand Down
Expand Up @@ -46,7 +46,6 @@

#include "as2_core/node.hpp"
#include "basic_motion_references.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

namespace as2 {
namespace motionReferenceHandlers {
Expand Down
Expand Up @@ -39,7 +39,6 @@

#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <as2_state_estimator/plugin_base.hpp>
#include <rclcpp/duration.hpp>
namespace mocap_pose {
Expand Down

0 comments on commit ece064c

Please sign in to comment.