From 38079342fff4d3f0e3f33667474ea1edad60703a Mon Sep 17 00:00:00 2001 From: Sem van der Hoeven Date: Tue, 2 May 2023 15:40:54 +0200 Subject: [PATCH] change to attitude --- src/px4_connection/src/px4_controller.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/px4_connection/src/px4_controller.cpp b/src/px4_connection/src/px4_controller.cpp index e5d88b3b..104a4e73 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 // #include @@ -39,7 +39,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)); // create timer to send vehicle attitude setpoints every second timer_ = this->create_wall_timer(100ms, std::bind(&PX4Controller::send_setpoint, this)); @@ -52,7 +52,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,16 +72,16 @@ private: void set_setpoint( const std::shared_ptr request_header, - const std::shared_ptr request, - const std::shared_ptr response) + 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->z_speed; + last_setpoint[0] = degrees_to_radians(request->yaw); + last_setpoint[1] = degrees_to_radians(request->pitch); + last_setpoint[2] = degrees_to_radians(request->roll); - last_angle = request->angle; + last_thrust = request->thrust; - RCLCPP_INFO(this->get_logger(), "New setpoint: x:%f y:%f z:%f angle:%f",last_setpoint[0],last_setpoint[1],last_setpoint[2], last_angle); + RCLCPP_INFO(this->get_logger(), "New setpoint: yaw:%f pitch:%f roll:%f thrust:%f", last_setpoint[0], last_setpoint[1], last_setpoint[2], last_thrust); response->status = 0; }