From 64464d06a5ed4fef1af1efd577b1ea95a3f0ddfe Mon Sep 17 00:00:00 2001 From: Sem van der Hoeven Date: Mon, 1 May 2023 16:07:49 +0200 Subject: [PATCH] remove srv from px4controller --- src/px4_connection/src/px4_controller.cpp | 28 +++++++++++------------ 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/src/px4_connection/src/px4_controller.cpp b/src/px4_connection/src/px4_controller.cpp index e614531b..9ff112ca 100644 --- a/src/px4_connection/src/px4_controller.cpp +++ b/src/px4_connection/src/px4_controller.cpp @@ -19,7 +19,7 @@ https://discuss.px4.io/t/cannot-arm-drone-with-companion-computer-arming-denied- #include #include -#include + // #include #define D_SPEED(x) -x - 9.81 @@ -37,7 +37,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", std::bind(&PX4Controller::set_setpoint, this, std::placeholders::_1,std::placeholders::_2,std::placeholders::_3)); + // set_attitude_service_ = this->create_service("set_attitude", std::bind(&PX4Controller::set_setpoint, this, std::placeholders::_1,std::placeholders::_2,std::placeholders::_3)); // service_ptr_ = this->create_service( // "test_service", @@ -55,7 +55,7 @@ private: rclcpp::Publisher::SharedPtr vehicle_setpoint_publisher_; rclcpp::Publisher::SharedPtr trajectory_setpoint_publisher; rclcpp::Publisher::SharedPtr vehicle_command_publisher_; - rclcpp::Service::SharedPtr set_attitude_service_; + // rclcpp::Service::SharedPtr set_attitude_service_; // rclcpp::Publisher::SharedPtr offboard_control_mode_publisher_; @@ -72,19 +72,19 @@ private: float last_setpoint[3] = {0,0,0}; float last_angle = 0; - void set_setpoint( - const std::shared_ptr request_header, - const std::shared_ptr request, - const std::shared_ptr response) - { - last_setpoint[0] = request->x_speed; - last_setpoint[1] = request->y_speed; - last_setpoint[2] = request->x_speed; + // void set_setpoint( + // const std::shared_ptr request_header, + // const std::shared_ptr request, + // const std::shared_ptr response) + // { + // last_setpoint[0] = request->x_speed; + // last_setpoint[1] = request->y_speed; + // last_setpoint[2] = request->x_speed; - last_angle = degrees_to_radians(request->angle); + // last_angle = degrees_to_radians(request->angle); - response->status = 0; - } + // response->status = 0; + // } void send_trajectory_setpoint() {