Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add one shot mode #6678

Merged
merged 32 commits into from
Mar 23, 2017
Merged

Add one shot mode #6678

merged 32 commits into from
Mar 23, 2017

Conversation

LorenzMeier
Copy link
Member

This adds one shot mode, done by @kd0aij - I'm merely assisting with the integration and continuing this PR: #6616

@LorenzMeier LorenzMeier force-pushed the kd0aij-add_oneshot_mode branch from 4a1a7f2 to b391821 Compare February 27, 2017 07:47
@LorenzMeier LorenzMeier mentioned this pull request Feb 27, 2017
3 tasks
@greybush
Copy link

greybush commented Mar 1, 2017

i am intrested to know the advice that would be given about hacking counter frequency?

@davids5
Copy link
Member

davids5 commented Mar 1, 2017

@greybush

The best reference is the STM32 reference manual for the SoC. The complications come in from the fact that all stm32 timers are not the same. Some have 32 bit regs others do not. There is an appnote that explains the differences. The other consideration is all PX4 bards provide a table of timers/ channels.

The normal useage is to set the prescaler to divide by the input freq/1Mhz so the counter 1 counts per 1uS. All the rates are based on 1uS resolution.

@davids5 davids5 force-pushed the kd0aij-add_oneshot_mode branch from b391821 to e33af23 Compare March 1, 2017 22:26
@davids5
Copy link
Member

davids5 commented Mar 1, 2017

Continuing

Rebased on master e892a51

Per @LorenzMeier
Threading / work queue should be runtime
125 nS preferred if feasible

pwm_limit_calc(should_arm, should_arm_nothrottle, mixed, r_setup_pwm_reverse, r_page_servo_disarmed,
r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
/* if mixer_mix_threadsafe returns zero, it did nothing */
if (mixed != 0) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@kd0aij @LorenzMeier I am not familiar with the mixer part of the system. I have some questions.

What does it mean to not be mixed?

The GH diff is hard to read - this is the change:
image

It looks like prior to this change, a mixed = 0 clamped all the outputs. And then updated r_page_actuators[i] to the clamped values. With the change the the clamping and updating will not happen is that the desired effect?

Or would

image

be a proper change?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It looked like a nasty bug to me (forcing all outputs to zero because something is locked?), but it's quite possible I don't understand how/why the code works.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you @kd0aij - I will wait for @LorenzMeier to chime in.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@kd0aij as far as I understand it when mixed (number of outputs mixed) is 0, it should clamp everything to 0 (off). It would mean that the mixing failed or the loaded mixer is invalid, etc.

Or is this not what you're discussing?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

under what conditions will mixing "fail"? can this happen in flight. and if so, why?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can this happen in flight. and if so, why?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point, I didn't see that. Let's check:

Before a new mixer is set, the flag is reset:
https://github.com/PX4/Firmware/blob/e7db0ed098bcc030042aba0667d09da67c130ffe/src/modules/px4iofirmware/mixer.cpp#L483

If a mixer is set/sent correctly the flag is set:
https://github.com/PX4/Firmware/blob/27abc4fe6b07a214125af7ea7f595f2d0bb15bb8/src/drivers/px4io/px4io.cpp#L2304

If overflow occurs in setting the mixer, the flag is also reset:
https://github.com/PX4/Firmware/blob/e7db0ed098bcc030042aba0667d09da67c130ffe/src/modules/px4iofirmware/mixer.cpp#L514

I don't see any other place where this flag is set, so it looks like there is no chance this will be triggered in flight, unless you send a new mixer, and that's probably forbidden as well.

Copy link
Member

@davids5 davids5 Mar 3, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Like I said - I am not familiar with this part of the system. So I am deferring to the experts.

My assumption is the original author (OA) had an intent. Just as @kd0aij does.

@kd0aij Do I understand, correctly, that your intent is to only update the Oneshots on valid Mix?

As far as the OA - Could this be perhaps a form of "lazy initialization" or have some side effect I do not understand?

@kd0aij If your intent was not to fire the update. Then proposed change does that and does not change the original intent.

To me that is the safest approach.

@kd0aij If it does not matter if up_pwm_force_update is called on a bad mix, then whole if can come out.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be bad to call up_pwm_force_update with the wrong output value, and very difficult to diagnose.
Perhaps the comment "poor mans mutex" could be more informative, as well. I got very tired of trying to divine the OA's intent. Of course my intent is always obvious :)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree that the comment is misleading.

Copy link
Contributor

@julianoes julianoes left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What jitter did you see when it ran in the high priority work queue instead of in its own task?

@@ -838,8 +877,10 @@ PX4FMU::publish_pwm_outputs(uint16_t *values, size_t numvalues)
void
PX4FMU::work_start()
{
#ifndef PX4FMU_TASK
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would put the #ifndef around the whole function. That way you can't accidentally call it.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@julianoes - I am in the midst of testing changes. I will be pushing changes soon where the fmu has a command line option [task] so the modality will be runtime.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wow, even fancier.

pwm_limit_calc(should_arm, should_arm_nothrottle, mixed, r_setup_pwm_reverse, r_page_servo_disarmed,
r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
/* if mixer_mix_threadsafe returns zero, it did nothing */
if (mixed != 0) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@kd0aij as far as I understand it when mixed (number of outputs mixed) is 0, it should clamp everything to 0 (off). It would mean that the mixing failed or the loaded mixer is invalid, etc.

Or is this not what you're discussing?

@@ -654,7 +657,7 @@ pwm_main(int argc, char *argv[])
}
}

usleep(2000);
usleep(2500);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why this?

@davids5
Copy link
Member

davids5 commented Mar 3, 2017

as far as I understand it when mixed (number of outputs mixed) is 0, it should clamp everything to 0 (off). It would mean that the mixing failed or the loaded mixer is invalid, etc.

Or is this not what you're discussing?

@julianoes - Thank you for the feedback. I am am out of my element here. So guidance is much appreciated.

@kd0aij, given @julianoes - would my proposed change accomplish what your intent was? If not please let me know how you would like the done.

@kd0aij
Copy link
Contributor

kd0aij commented Mar 3, 2017 via email

@davids5 davids5 force-pushed the kd0aij-add_oneshot_mode branch from 21b392b to a427092 Compare March 3, 2017 22:49
davids5 pushed a commit that referenced this pull request Mar 3, 2017
   As discusssed in #6678 (comment)
   this take the safe approach to only call up_pwm_update on a valid mix
   it does keep intatct the riginal author (OA) had an intent.
Copy link
Member

@davids5 davids5 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@LorenzMeier - Please review.

@kd0aij - Would you please help test this?

If you have a set of command line pwm and parameter commands that you use that would be super helpful.

I did not modify the rcS to add the word task to the FMU commands.

@@ -951,7 +951,7 @@ PX4IO::task_main()
* primary PWM output or not.
*/
_t_actuator_controls_0 = orb_subscribe(ORB_ID(actuator_controls_0));
orb_set_interval(_t_actuator_controls_0, 20); /* default to 50Hz */
// orb_set_interval(_t_actuator_controls_0, 20); /* default to 50Hz */
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@LorenzMeier - I need you to have a look at the change the above and Line 3530 below.

@@ -3527,6 +3527,8 @@ test(void)
}
}

usleep(250);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same Here

@kd0aij
Copy link
Contributor

kd0aij commented Mar 3, 2017

@davids5 Is there a unit test for this? Does this implementation allow both PWM and oneshot channels in the same timer?

@davids5
Copy link
Member

davids5 commented Mar 3, 2017

@kd0aij -

No a timer can only be in one mode - so all channels in group (timer) are in the same mode.

I think we do need to have a mode in the FMU to get the default rate and alt rates to set to 0.

@kd0aij
Copy link
Contributor

kd0aij commented Mar 4, 2017

@davids5 From my post on the forum topic: "the only parameter change required is to set PWM_RATE to zero. Leave PWM min/max/disarmed at the "normal" values." You should see jitter on the output pulses and the frequency should average 250Hz.
http://discuss.px4.io/t/px4-oneshot125/303/36?u=mark_whitehorn

@davids5
Copy link
Member

davids5 commented Mar 4, 2017

@kd0aij Did you only test with a quad?

Even with PWM_RATE = 0

pwm oneshot -m 0xf -g 0 -d /dev/pwm_output0
pwm oneshot -m 0x30 -g 1 -d /dev/pwm_output0

The second command - would bounce the first set back to the non zero value of _pwm_default_rate

I could not see a way to get the fmu variables:

_pwm_default_rate = 0;
_pwm_alt_rate = 0;

The last commit does that. - We can back it out if it is not need.

@kd0aij
Copy link
Contributor

kd0aij commented Mar 4, 2017

I've never used the -m switch; doesn't that imply you can set channel modes arbitrarily? I only used -g myself. I'm not aware of any documentation explaining the logic (or lack thereof).
What do you mean by "test with a quad"? I wasn't aware that the timer outputs were dependent on the airframe type, and would demand that timer modes are orthogonal to airframe type.

@davids5
Copy link
Member

davids5 commented Mar 4, 2017

@kd0aij I was asking if you had tested (or scopped) more than 4 servo outs?

@LorenzMeier
Copy link
Member Author

@PX4TestFlights Can you test this on a racer and see if you can increase rate gains?

@kd0aij
Copy link
Contributor

kd0aij commented Mar 4, 2017

@davids5 I tested both fmu and px4io as stated here: #6616 (comment)

@davids5
Copy link
Member

davids5 commented Mar 4, 2017

@LorenzMeier

  1. rcS may need to be augmented to used the task option on fmu.
  2. We may need more work on the pio. In Add one shot mode #6678 (comment) I described the how The second command - would bounce the first set back to the non zero value of _pwm_default_rate. Thy may just be my lack of understanding of how to get the default and alt rates set to 0. Hence commit 22738b1. How would this be done for the pio?

Testing verification:

It is my understanding that an ESC will not outwardly appear to act differently if the given input it supplied as PWM or Oneshot.

@PX4TestFlights - do you have a oscilloscope and a octo to test on?

When testing please configure the craft and then verify that the all 8 channels are in oneshot mode with a oscilloscope. The PWM pins should not have high times > 250uS

@kd0aij
Copy link
Contributor

kd0aij commented Mar 4, 2017

@davids5 What is the definition of channel "group" and "mask"? Are they orthogonal, as is implied by some of the comments in the code?

@davids5
Copy link
Member

davids5 commented Mar 4, 2017

@kd0aij - Do you have a link to the comment you are referring to.

It is my understanding in general that the group is the timer and the mask is the channels on that timer to affect, The mask is the channel number's bit position. So channel 5 & 6 is 0x30 not 0x03

But the latter is command dependant.

On a FMUv4 - no PX4IO

device: /dev/pwm_output0
channel 1: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel 2: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel 3: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel 4: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel 5: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel 6: 0 us (default rate: 50 Hz failsafe: 0, disarmed: 0 us, min: 1000 us, max: 2000 us, trim:  0.00)
channel group 0: channels 1 2 3 4
channel group 1: channels 5 6

So for pwm -g 1 -m 0x30 -d /dev/pwm_output0
is setting the group 1 to use the alt rate. The -m is the alt rate selection mask

So for pwm -g 1 -m 0 -d /dev/pwm_output0
is setting the group 1 to use the default rate. The -m is the alt rate selection mask

But I think the complication comes in here:

This says a group (aka timer) has a bit mask of channels and you asking to modify a rate not on this group.
Effectively enforcing the all channels on this timer or nothing rule

@kd0aij
Copy link
Contributor

kd0aij commented Mar 4, 2017

Then it is at best misleading to require specifying both group and mask, and likely indicative of a design flaw.

@LorenzMeier
Copy link
Member Author

Its not a design flaw. The current design requires all outputs of a timer to have the same rate (in theory multiples of a rate would be feasible and maybe what we want here to ease up the constraints).

The mask applies to all outputs of s PWM device and allows you to pick multiple timers at once and is more intuitive than specifying timers.

However, while this design closely reflects the HW I think we should switch so outputs at multiples of a rate become feasible. So 400 Hz and 50 Hz can be mixed, 300 and 400 Hz could not. That would make the airframe config much easier and only minimally increase the driver complexity and runtime interrupt load.

@LorenzMeier
Copy link
Member Author

@davids5 Can you rebase and get this ready for flight testing?

@davids5 davids5 force-pushed the kd0aij-add_oneshot_mode branch from f0c3ec5 to 5433607 Compare March 10, 2017 19:48
davids5 pushed a commit that referenced this pull request Mar 10, 2017
   As discusssed in #6678 (comment)
   this take the safe approach to only call up_pwm_update on a valid mix
   it does keep intatct the riginal author (OA) had an intent.
David Sidrane and others added 15 commits March 13, 2017 21:55
  At at a period greater than the the max Oneshot pulse width
  Trigger all timer's channels in Oneshot mode to fire the
  oneshots with updated values.
  1) Validate timer paramater before using it.
  2) Allow rate of 0 to enter Oneshot mode
     At first blush this seamed like a hack, but at Mark
     pointed out to me, Onshot PWM does not have a rate
     So this is a realy a clever and beautiful simplification
     on his part!
  3) Exposes up_pwm_update that runs io_timer_trigger
     Which trigger all timer's channels in Oneshot mode to
     fire the oneshots with updated values.
   1) Use up_pwm_retrigger to triger onshot
   2) Updated comment to explain why a rate of zero makes sense
      to set oneshot mode.
   3) Updated copyright
   As discusssed in #6678 (comment)
   this take the safe approach to only call up_pwm_update on a valid mix
   it does keep intatct the riginal author (OA) had an intent.
   1) Define IOTimerChanMode_OneShot
   2) Added detailed commnent on .clock_freq and how it is used
   3) Added single additional API point in support of Onshot mode
      io_timer_trigger - That trigger all timer's channels in Oneshot
      mode to fire the oneshots with updated values.
  1) Updated copyright
  2) Defined BOARD overrideable BOARD_PWM_FREQ and BOARD_ONSHOT_FREQ
     Not recogmended but allow experimentation
  3) Solved the support for BOARD_PWM_DRIVE_ACTIVE_LOW using
     the Polarity control bits as apposed to the negation of
     the ARR.
  4) Added a cache for getting a timers channels. This is static
     and benifits from the qucik response.
  5) Added a function to realocate all channes in a given timer
     from one mode to another.
  6) Removed the frequecy table in favor of the intended use of the
     channel mode set. At it is the way to determine the mode of a
     channel. Or in onshot's case a timers's complete set channels.
  7) Added 2 lowlevel mode changing functions:
     io_timer_set_oneshot_mode and io_timer_set_PWM_mode
     that encapsalate the changes in mode to one place
     in the code.
  8) Added io_timer_trigger (the up_pwm_update) with low
     latancy timer to time in updating.
  9) io_timer_set_rate - use sets to enforce all or none
     rules for switching  PWM<->OneShot.
     Onshot is entered using the very approriate rate of 0.
     Only deltas will change the HW state.
 Since the Onshot<->PWM mode is changed based on rate. The
 this signale the higher layers that the operation is invalid

 test case:
   fmu task mode_pwm2cap2
   pwm oneshot -m 0xf -g 0 -d /dev/pwm_output0

   should fail, because all the channels in the group are
   not in the same mode.
   This reverts commit 22738b1.

   The command was added due to a lack of my understanding of how the pwm command can be used.

   The command is not needed as the all flag can be used or a proper
   mask WHIHOUT -g

   fmu task mode_pwm
   pwm rate -a -r 50 -d /dev/pwm_output0
   pwm arm
   pwm test -a -p 500

   fmu task mode_pwm
   pwm oneshot -a -d /dev/pwm_output0 is the same as pwm oneshot -m 0xff  -d /dev/pwm_output0
   pwm arm
   pwm test -a -p 500
@LorenzMeier LorenzMeier force-pushed the kd0aij-add_oneshot_mode branch from 1511fc6 to 695e405 Compare March 13, 2017 20:59
@LorenzMeier
Copy link
Member Author

@MaEtUgR @julianoes Something for you to try - I'll get you Mindracer frames.

@santiago3dr
Copy link

Flashed a pixhawk mini with this PR and it caused issues where RCin was not detected
was able to reproduce this and record, video below:
https://youtu.be/OsBB4cGbe54

@LorenzMeier
Copy link
Member Author

@davids5 Can you look at the RC in detection problem with Santiago?

@santiago3dr
Copy link

broken RCin mentioned earlier was due to pull being outdated
old commit: 1511fc6
new commit: 695e405

@davids5
Copy link
Member

davids5 commented Mar 14, 2017

@santiago3dr

Would you please flight test it as well?

Also please advise if you can do what is listed here with a scope once setting PWM rates to 0

@greybush
Copy link

is the oneshot125 finished and added to the flight stack yet?

@davids5
Copy link
Member

davids5 commented Mar 23, 2017

@greybush - it is not merged yet. You can test it from here if you like.

@davids5 davids5 closed this Mar 23, 2017
@davids5 davids5 reopened this Mar 23, 2017
@LorenzMeier LorenzMeier merged commit fd0efac into master Mar 23, 2017
LorenzMeier pushed a commit that referenced this pull request Mar 23, 2017
   As discusssed in #6678 (comment)
   this take the safe approach to only call up_pwm_update on a valid mix
   it does keep intatct the riginal author (OA) had an intent.
@LorenzMeier LorenzMeier deleted the kd0aij-add_oneshot_mode branch March 23, 2017 07:29
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

7 participants