forked from Archive/PX4-Autopilot
PWM output limiter: Improve comments.
This commit is contained in:
parent
a33700a7ec
commit
cde8d72694
|
@ -1,7 +1,6 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
|
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
|
||||||
* Author: Julian Oes <joes@student.ethz.ch>
|
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -35,9 +34,9 @@
|
||||||
/**
|
/**
|
||||||
* @file pwm_limit.c
|
* @file pwm_limit.c
|
||||||
*
|
*
|
||||||
* Lib to limit PWM output
|
* Library for PWM output limiting
|
||||||
*
|
*
|
||||||
* @author Julian Oes <joes@student.ethz.ch>
|
* @author Julian Oes <julian@px4.io>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "pwm_limit.h"
|
#include "pwm_limit.h"
|
||||||
|
@ -46,6 +45,8 @@
|
||||||
#include <drivers/drv_hrt.h>
|
#include <drivers/drv_hrt.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
|
#define PROGRESS_INT_SCALING 10000
|
||||||
|
|
||||||
void pwm_limit_init(pwm_limit_t *limit)
|
void pwm_limit_init(pwm_limit_t *limit)
|
||||||
{
|
{
|
||||||
limit->state = PWM_LIMIT_STATE_INIT;
|
limit->state = PWM_LIMIT_STATE_INIT;
|
||||||
|
@ -112,7 +113,11 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
|
||||||
{
|
{
|
||||||
hrt_abstime diff = hrt_elapsed_time(&limit->time_armed);
|
hrt_abstime diff = hrt_elapsed_time(&limit->time_armed);
|
||||||
|
|
||||||
progress = diff * 10000 / RAMP_TIME_US;
|
progress = diff * PROGRESS_INT_SCALING / RAMP_TIME_US;
|
||||||
|
|
||||||
|
if (progress > PROGRESS_INT_SCALING) {
|
||||||
|
progress = PROGRESS_INT_SCALING;
|
||||||
|
}
|
||||||
|
|
||||||
for (unsigned i=0; i<num_channels; i++) {
|
for (unsigned i=0; i<num_channels; i++) {
|
||||||
|
|
||||||
|
@ -128,7 +133,7 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned disarmed_min_diff = min_pwm[i] - disarmed;
|
unsigned disarmed_min_diff = min_pwm[i] - disarmed;
|
||||||
ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / 10000;
|
ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / PROGRESS_INT_SCALING;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
|
|
|
@ -1,7 +1,6 @@
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
|
||||||
* Author: Julian Oes <joes@student.ethz.ch>
|
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -33,11 +32,11 @@
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file pwm_limit.h
|
* @file pwm_limit.c
|
||||||
*
|
*
|
||||||
* Lib to limit PWM output
|
* Library for PWM output limiting
|
||||||
*
|
*
|
||||||
* @author Julian Oes <joes@student.ethz.ch>
|
* @author Julian Oes <julian@px4.io>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef PWM_LIMIT_H_
|
#ifndef PWM_LIMIT_H_
|
||||||
|
|
Loading…
Reference in New Issue