Closed serkanMzlm closed 1 month ago
My goal is to get PWM output to run the 6 motors I have installed externally, in addition to the 4 motors required to fly the drone.
Hello, did you put the drone into offboard mode? Where you able to arm?
@beniaminopozzan Yes, it goes into offboard mode and when I arm it, there is no change in the PWM output. The "ros2 topic echo /fmu/out/vehicle_status" command runs in the terminal on the right.
Note: I can control the engines in the Gazebo simulation environment with these codes, but I cannot do this in the real PX4.
There is also a problem in the simulation environment, the engines disarm after a certain period of time, but the engines I will add as extras are not engines related to drone flight dynamics, so they should not only depend on the arm disarm status.
What should I set the outputs on the IO port to?
Did you follow: https://docs.px4.io/main/en/config/actuators.html? If you do not assign motor outputs, you do not get a motor output.
@AlexisTM The motors selection is set to "main 1 -> peripheral via actuator set 1", but is this correct, for example? How do I know which ports control which outputs between ActuatorMotors and ActuatorServos?
QGC only has motor 1 2 3 4, there is no servo option.
@AlexisTM The motors selection is set to "main 1 -> peripheral via actuator set 1", but is this correct, for example? How do I know which ports control which outputs between ActuatorMotors and ActuatorServos?
If you want to use fmu/in/actuator_motors
then you should set your motors (in the actuator tabs) as Motor 1
, Motor 2
, etc
This allows you to switch between different modes (Offboard, Position, etc) because PX4 will map the internal thrust and torque setpoints to motor commands. This is done by the control allocator if the output is set as Motor x
. Of course, in Offboard mode with direct command the control allocator is disabled.
If you want to configure your Motors as Periferal with actuator set z
then you should use refer to https://docs.px4.io/main/en/payloads/generic_actuator_control.html#generic-actuator-control-with-mavlink
In this scenario you have to send a vehicleCommand
message that repliates MAV_CMD_DO_SET_ACTUATOR
See here for the implementation: https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/mixer_module/functions/FunctionActuatorSet.hpp
tl,dr: send a VehicleCommand message with command VEHICLE_CMD_DO_SET_ACTUATOR = 187
and the desired output on the paramx
fields.
I'd need to double check why it works on gazebo but not on reality. My guess is that Gazebo blindly listens to the actuatorMotor topic so the actual motor assignment is ignored
@beniaminopozzan Currently, as a solution, I send VEHICLE_CMD_ACTUATOR_TEST and send the value of whichever engine I want to control. This way it worked perfectly.
vehicleCommandMsg msg{};
msg.param1 = param1;
msg.param2 = 1.0f;
msg.param5 = 1300.0f + param5;
msg.command = vehicleCommandMsg::VEHICLE_CMD_ACTUATOR_TEST;
msg.target_system = 1;
msg.target_component = 1;
msg.source_system = 255;
msg.source_component = 1;
msg.from_external = true;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
pub.vehicle_command->publish(msg);
@beniaminopozzan Currently, as a solution, I send VEHICLE_CMD_ACTUATOR_TEST and send the value of whichever engine I want to control. This way it worked perfectly.
vehicleCommandMsg msg{}; msg.param1 = param1; msg.param2 = 1.0f; msg.param5 = 1300.0f + param5; msg.command = vehicleCommandMsg::VEHICLE_CMD_ACTUATOR_TEST; msg.target_system = 1; msg.target_component = 1; msg.source_system = 255; msg.source_component = 1; msg.from_external = true; msg.timestamp = this->get_clock()->now().nanoseconds() / 1000; pub.vehicle_command->publish(msg);
@serkanMzlm Hi, I am trying to acheive the same solution. did you have to send the px4_msgs::msg::OffboardControlMode message in addition to sending the Vehicle command msg?
@mohdkhanBechamo All you have to do is find your engine numbers and simply broadcast the vehicleCommandMsg message.
Describe the bug
I broadcast "fmu/in/actuator_motors" for actuator control in offboard mode, but there was no change in the PWM signal at the IO or FMU outputs.
To Reproduce
I connected the PX4 to the computer.
I made the necessary settings in the PX4 section for MicroXRCEAgent and connected it to the computer with the FTDI cable.
I published a message of type px4_msgs::msg::OffboardControlMode.
I published a message of type px4_msgs::msg::ActuatorMotors.
Expected behavior
In this part, I waited for the PWM to change at the IO or FMU outputs.
Screenshot / Media
No response
Flight Log
No response
Software Version
1.15
Flight controller
No response
Vehicle type
Multicopter
How are the different components wired up (including port information)
There is no problem with the wiring
Additional context
No response