Hello, I am recently learning to use PX4 for simulations on a drone in Gazebo Garden. I am trying to implement my Offboard controller, which should send values between -1 and 1 to the actuators. I have tried modifying the offboard_control
file provided as an example in the px4_ros_com
package by removing the position control part and attempting to send messages of type VehicleCommand
to set the motor values. Once I start the package, the flight mode switches to Offboard mode in QGC, but the drone doesn’t arm, and I get the “No offboard signal” error. Can someone help me?
I am using Ubuntu 22.04 with ROS2 Humble and Gazebo Garden. Additionally, is there a way to directly send the desired RPM to the actuators?
#include <px4_msgs/msg/offboard_control_mode.hpp>
#include <px4_msgs/msg/vehicle_command.hpp>
#include <rclcpp/rclcpp.hpp>
using namespace std::chrono;
using namespace std::chrono_literals;
using namespace px4_msgs::msg;
class OffboardControl : public rclcpp::Node
{
public:
OffboardControl() : Node("offboard_control")
{
offboard_control_mode_publisher_ = this->create_publisher<OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
vehicle_command_publisher_ = this->create_publisher<VehicleCommand>("/fmu/in/vehicle_command", 10);
offboard_setpoint_counter_ = 0;
auto timer_callback = [this]() -> void {
if (offboard_setpoint_counter_ == 10)
{
// Cambia alla modalità Offboard dopo 10 setpoint
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
this->arm();
}
this->publish_offboard_control_mode();
this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_ACTUATOR, 1.0, 0.5);
if (offboard_setpoint_counter_ < 11)
{
offboard_setpoint_counter_++;
}
};
timer_ = this->create_wall_timer(100ms, timer_callback);
}
void arm();
void disarm();
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
rclcpp::Publisher<VehicleCommand>::SharedPtr vehicle_command_publisher_;
std::atomic<uint64_t> timestamp_; //!< common synced timestamped
uint64_t offboard_setpoint_counter_; //!< counter for the number of setpoints sent
void publish_offboard_control_mode();
void publish_vehicle_command(uint16_t command, float param1 = 0.0, float param2 = 0.0);
};
void OffboardControl::arm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0);
RCLCPP_INFO(this->get_logger(), "Arm command send");
}
void OffboardControl::disarm()
{
publish_vehicle_command(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0.0);
RCLCPP_INFO(this->get_logger(), "Disarm command send");
}
void OffboardControl::publish_offboard_control_mode()
{
OffboardControlMode msg{};
msg.position = false;
msg.velocity = false;
msg.acceleration = false;
msg.attitude = false;
msg.body_rate = false;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
offboard_control_mode_publisher_->publish(msg);
}
void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2)
{
VehicleCommand msg{};
msg.param1 = param1;
msg.param2 = param2;
msg.command = command;
msg.target_system = 1;
msg.target_component = 1;
msg.source_system = 1;
msg.source_component = 1;
msg.from_external = true;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
vehicle_command_publisher_->publish(msg);
}
int main(int argc, char *argv[])
{
std::cout << "Starting offboard control node..." << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<OffboardControl>());
rclcpp::shutdown();
return 0;
}