change px4 controller to setvelocity service
This commit is contained in:
@@ -19,7 +19,7 @@ https://discuss.px4.io/t/cannot-arm-drone-with-companion-computer-arming-denied-
|
||||
#include <px4_msgs/msg/vehicle_command.hpp>
|
||||
#include <px4_msgs/msg/vehicle_control_mode.hpp>
|
||||
|
||||
#include <drone_services/srv/set_attitude.hpp>
|
||||
#include <drone_services/srv/set_velocity.hpp>
|
||||
|
||||
|
||||
// #include <px4_msgs/msg/offboard_control_mode.hpp>
|
||||
@@ -39,7 +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<drone_services::srv::SetAttitude>("set_attitude", std::bind(&PX4Controller::set_setpoint, this, std::placeholders::_1,std::placeholders::_2,std::placeholders::_3));
|
||||
set_attitude_service_ = this->create_service<drone_services::srv::SetVelocity>("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<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<drone_services::srv::SetAttitude>::SharedPtr set_attitude_service_;
|
||||
rclcpp::Service<drone_services::srv::SetVelocity>::SharedPtr set_attitude_service_;
|
||||
|
||||
// rclcpp::Publisher<px4_msgs::msg::OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
|
||||
|
||||
@@ -71,8 +71,8 @@ private:
|
||||
|
||||
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)
|
||||
const std::shared_ptr<drone_services::srv::SetVelocity::Request> request,
|
||||
const std::shared_ptr<drone_services::srv::SetVelocity::Response> response)
|
||||
{
|
||||
last_setpoint[0] = request->x_speed;
|
||||
last_setpoint[1] = request->y_speed;
|
||||
|
||||
Reference in New Issue
Block a user