How to set PWM minimum to zero?

Hello,
Is it possible to set the minimum value of PWM output to zero? I want to output a PWM signal ranging between 0 to 2000 microseconds from one of the main output pins of pixhawk.

I used the command “pwm min -c 6 -p 0” but it only decreases the minimum value up till 90 microseconds. If I use anything less than 90 in the command, the minimum still stays at 90.

I believe it is possible to set it to 0 because the throttle channel also outputs 0 when unarmed. I tried finding how the pwm output for throttle channel works but didn’t succeed.

Please let me know if it is possible. If not, is there any alternative like using one of the aux pins whose output can change from digital to pwm using a toggle switch. Thanks!

Update: Finally, I could set PWM minimum to 0 microseconds by modifying the following file src/modules/px4iofirmware/registers.c

	case PX4IO_PAGE_CONTROL_MIN_PWM:
                         /* copy channel data */
	while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {

		if (*values == 0) {
			/* ignore 0 */
		} else if (*values > PWM_HIGHEST_MIN) {
			r_page_servo_control_min[offset] = PWM_HIGHEST_MIN;

		} else if (*values < PWM_LOWEST_MIN) {
			r_page_servo_control_min[offset] = PWM_LOWEST_MIN;

		} else {
			r_page_servo_control_min[offset] = *values;
		}

		offset++;
		num_values--;
		values++;
	}

I wanted channel 6 minimum PWM output to be zero. So I added the following line inside the while loop after the if-else statement and it worked.

r_page_servo_control_min [5] = 0;