From 3d8074e8230419efd5bb277f8a78cb5ab5de7dc2 Mon Sep 17 00:00:00 2001 From: Sem van der Hoeven Date: Thu, 25 May 2023 12:10:24 +0200 Subject: [PATCH] remove this --- src/drone_controls/src/PositionChanger.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/drone_controls/src/PositionChanger.cpp b/src/drone_controls/src/PositionChanger.cpp index fa503b54..8da28b2c 100644 --- a/src/drone_controls/src/PositionChanger.cpp +++ b/src/drone_controls/src/PositionChanger.cpp @@ -39,15 +39,15 @@ public: rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 5), qos_profile); - this->lidar_subscription = this->create_subscription("/drone/object_detection", qos, std::bind(&PositionChanger::handle_lidar_message, this)); + lidar_subscription = this->create_subscription("/drone/object_detection", qos, std::bind(&PositionChanger::handle_lidar_message, this,std::placeholders::_1)); // vehicle_local_position_subscription_ = this->create_subscription("/fmu/out/vehicle_local_position", qos, std::bind(&PX4Controller::on_local_position_receive, this, std::placeholders::_1)); - this->odometry_subscription = this->create_subscription("/fmu/out/vehicle_odometry", qos, std::bind(&PositionChanger::handle_odometry_message, this, std::placeholders::_1)); - this->move_position_service = this->create_service("/drone/move_position", std::bind(&PositionChanger::handle_move_position_request, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - - this->trajectory_client = this->create_client("/drone/set_trajectory"); - this->vehicle_control_client = this->create_client("/drone/set_vehicle_control"); + odometry_subscription = this->create_subscription("/fmu/out/vehicle_odometry", qos, std::bind(&PositionChanger::handle_odometry_message, this, std::placeholders::_1)); + move_position_service = this->create_service("/drone/move_position", std::bind(&PositionChanger::handle_move_position_request, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); + trajectory_client = this->create_client("/drone/set_trajectory"); + vehicle_control_client = this->create_client("/drone/set_vehicle_control"); + RCLCPP_INFO(this->get_logger(), "waiting for trajectory service..."); wait_for_service::SharedPtr>(this->trajectory_client); RCLCPP_INFO(this->get_logger(), "waiting for vehicle control service...");