PWM/Servo Control via px4dev code Help

Hey all,
I need help in being able to control a servo via code - not using radio controller input.
I cannot control the PWM outputs of pins 6 and 7, and i dont know why, any help appreciated.
Using nsh terminal (pwm test -c 67 -p 1000) works as expected.

This is on the X-quadrotor configuration, Pixhawk FC.
I have also tried using topic actuator_controls_0 to test.

Aim is to set pin 6 to max pwm and pin 7 to min pwm.
Alternatively, i can use PWM AUX 1 and AUX 2 if easier.

I tried following bottle_drop.cpp code to get this.

Any suggestions?

This code is in task_main() in a custom app. Outputs in nsh terminal shows it definately gets into the loop.
NOTE: Do not refer me to the px4 gymbal example for gymbal control, as this is intentionally set up as a custom app for custom purposes.

warnx("Gymbal Control Started!");

while(!_task_should_exit)
{

  orb_copy(ORB_ID(external_cmd), _ext_cmd_sub, &_ext_cmd);

  // test
  _actuators.control[5] = 1.0f;
  _actuators.control[6] = -1.0f;
  _actuators.timestamp = hrt_absolute_time();

  if (_actuator_pub != nullptr) 
  {
	orb_publish(ORB_ID(actuator_controls_2), _actuator_pub, &_actuators);	
  } else 
  {
      _actuator_pub = orb_advertise(ORB_ID(actuator_controls_2), &_actuators);
  } 

    usleep(20000);
}

Thanks for any help you can provide!

1 Like

I had the same issue sadly, what I have done is that I used directly the ioctl() function instead.

Maybe you can try controlling directly with px4_ioctl() function : you can take inspiration on /src/systemcmds/motor_ramp.cpp for example.

the code controlling the actuators in file /src/systemcmds/motor_ramp.cpp in function set_out() is :

Parameters of ioctl in /nuttx/nuttx/include/sys/ioctl.h

  • fd File/socket descriptor of device
  • req The ioctl command
  • arg The argument of the ioctl cmd

where ioctl PWM_SERVO_SET is defined as :

Hope it can help you.

Hey,
Thanks, that solved my problem!

1 Like

Code is below:

The includes i used (note sure which i actually needed):

#include <px4_config.h>
#include <px4_defines.h>
#include <px4_tasks.h>
#include <px4_posix.h>
#include <systemlib/param/param.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include <platforms/px4_defines.h>
#include "systemlib/systemlib.h"
#include "systemlib/err.h"

Setup port specs:

// Setup PWM port params
const char *dev = PWM_OUTPUT0_DEVICE_PATH;
int fd = px4_open(dev, 0);
if (fd<0)
{ PX4_ERR("its dead jim!"); }

And finally execution of PWM control:

 int mode_ret =  px4_ioctl(fd, PWM_SERVO_SET(modeslot), set_pwm);
 int pitch_ret = px4_ioctl(fd, PWM_SERVO_SET(pitchslot), 1500);

Note: PWM pins are defined as 0-7 (not sure about AUX pins), must be armed to control the PWM outputs, PWM is defined from 0-2000 (Pixhawk prefers range 1000-2000).

Hope this helps anyone needing it.

1 Like

Just by curiosity is the app “motor_test iterate” is working on yours ? You have to stop mc_att_control and fw_att_control before trying.

Hey I am new to the community and to the px4 so please bear with me. I am trying to control a servo motor which is connected to the AUX1 port of the pixhawk 4. I want to set the PWM on AUX1 after crossing a particular way point in mission. Full mission is planned using dronecode sdk.
I am not able to figure out how to set the pwm? do i need to add a aux_mixer to the x-quad frame and then create a plugin on dronecode sdk to set the pwm? Please guide me through this topic.

1 Like

Is there any update regarding this?