add print of service
This commit is contained in:
@@ -24,7 +24,8 @@ public:
|
||||
HeartBeat() : Node("heartbeat")
|
||||
{
|
||||
// disarm_service_ = this->create_service<std_srvs::srv::Empty>("drone/disarm", std::bind(&PX4Controller::handle_disarm_request, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
|
||||
vehicle_control_mode_service_ = this->create_service<drone_services::srv::SetVehicleControl>("drone/set_vehicle_control", std::bind(&HeartBeat::handle_vehicle_control_change, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
|
||||
vehicle_control_mode_service_ = this->create_service<drone_services::srv::SetVehicleControl>("/drone/set_vehicle_control", std::bind(&HeartBeat::handle_vehicle_control_change, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
|
||||
RCLCPP_INFO(this->get_logger(), "initialized service /drone/set_vehicle_control");
|
||||
// create a publisher on the offboard control mode topic
|
||||
offboard_control_mode_publisher_ = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
|
||||
// create timer to send heartbeat messages (offboard control) every 100ms
|
||||
|
||||
Reference in New Issue
Block a user