add service back

This commit is contained in:
Sem van der Hoeven
2023-05-01 16:15:49 +02:00
parent 2513e56631
commit 767c658900

View File

@@ -39,12 +39,7 @@ public:
trajectory_setpoint_publisher = this->create_publisher<px4_msgs::msg::TrajectorySetpoint>("/fmu/in/trajectory_setpoint", 10);
// offboard_control_mode_publisher_ = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
// set_attitude_service_ = this->create_service<px4_connection::srv::SetAttitude>("set_attitude", std::bind(&PX4Controller::set_setpoint, this, std::placeholders::_1,std::placeholders::_2,std::placeholders::_3));
// service_ptr_ = this->create_service<std_srvs::srv::Empty>(
// "test_service",
// std::bind(&ServiceNode::service_callback, this, _1, _2, _3)
// );
set_attitude_service_ = this->create_service<drone_services::srv::SetAttitude>("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));
@@ -57,7 +52,7 @@ private:
rclcpp::Publisher<px4_msgs::msg::VehicleAttitudeSetpoint>::SharedPtr vehicle_setpoint_publisher_;
rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr trajectory_setpoint_publisher;
rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr vehicle_command_publisher_;
// rclcpp::Service<px4_connection::srv::SetAttitude>::SharedPtr set_attitude_service_;
rclcpp::Service<drone_services::srv::SetAttitude>::SharedPtr set_attitude_service_;
// rclcpp::Publisher<px4_msgs::msg::OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
@@ -74,19 +69,19 @@ private:
float last_setpoint[3] = {0,0,0};
float last_angle = 0;
// void set_setpoint(
// const std::shared_ptr<rmw_request_id_t> request_header,
// const std::shared_ptr<px4_connection::srv::SetAttitude::Request> request,
// const std::shared_ptr<px4_connection::srv::SetAttitude::Response> 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<rmw_request_id_t> request_header,
const std::shared_ptr<drone_services::srv::SetAttitude::Request> request,
const std::shared_ptr<drone_services::srv::SetAttitude::Response> 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()
{