From 8efa23948d6dfb37f7922d34c96693f4ae725b0a Mon Sep 17 00:00:00 2001 From: Sem van der Hoeven Date: Mon, 1 May 2023 15:53:39 +0200 Subject: [PATCH] no placeholders? --- src/px4_connection/src/px4_controller.cpp | 12 +----------- 1 file changed, 1 insertion(+), 11 deletions(-) diff --git a/src/px4_connection/src/px4_controller.cpp b/src/px4_connection/src/px4_controller.cpp index f7e2cdae..98d51a3e 100644 --- a/src/px4_connection/src/px4_controller.cpp +++ b/src/px4_connection/src/px4_controller.cpp @@ -30,15 +30,6 @@ using namespace std::placeholders; class PX4Controller : public rclcpp::Node { public: - - void yeet( - const std::shared_ptr request, - const std::shared_ptr response) - { - - - } - PX4Controller() : Node("px4_controller") { // create a publisher on the vehicle attitude setpoint topic @@ -47,8 +38,7 @@ public: trajectory_setpoint_publisher = this->create_publisher("/fmu/in/trajectory_setpoint", 10); // offboard_control_mode_publisher_ = this->create_publisher("/fmu/in/offboard_control_mode", 10); - set_attitude_service_ = this->create_service("set_attitude", &yeet); - // set_attitude_service_ = this->create_service("set_attitude", std::bind(&PX4Controller::set_setpoint, this, _1, _2, _3)); + set_attitude_service_ = this->create_service("set_attitude", std::bind(&PX4Controller::set_setpoint, this)); // service_ptr_ = this->create_service( // "test_service",