RX72T

Application Note: R01AN4721EJ0100 Rev.1.00, Mar 29, 2019

Vector Control for Permanent Magnet Synchronous Motor with Encoder (Implementation)

Abstract

This application note explains sample programs for a permanent magnet synchronous motor with encoder, utilizing the functions of the RX72T microcontroller. It covers how to use the library of the 'Renesas Motor Workbench' tool, which supports motor control development. The software provided is for reference only, and Renesas Electronics Corporation does not guarantee its operations. Users should conduct thorough evaluations in a suitable environment.

Operation Checking Device

The operations of the target software are checked using the following device:

  • RX72T (R5F572TKCDFB)

Target Software

The target programs for this application note are:

  • RX72T_MRSSK_SPM_ENCD_FOC_CSP_RV100 (IDE: CS+)
  • RX72T_MRSSK_SPM_ENCD_FOC_E2S_RV100 (IDE: e2studio)

This includes vector control with encoder software for the '24V Motor Control Evaluation System for RX23T' and 'RX72T CPU Card'.

Reference

  • RX72T Group User's Manual: Hardware (R01UH0803)
  • Application note: ‘Vector control for permanent magnet synchronous motor with encoder (Algorithm)' (R01AN3789)
  • Renesas Motor Workbench V.1.00 User's Manual (R21UZ0004)
  • Renesas Solution Starter Kit 24V Motor Control Evaluation System for RX23T User's Manual (R20UT3697)

1. Overview

This application note aims to explain the sample programs for a permanent magnet synchronous motor with encoder, by using functions of RX72T. The explanation includes how to use the library of the 'Renesas Motor Workbench' tool, which is a support tool for motor control development. These sample programs use the algorithm described in the application note ‘Vector control for permanent magnet synchronous motor with encoder (Algorithm)'.

1.1 Development environment

The following tables show the development environment for the sample programs described in this application note.

MicrocontrollerEvaluation boardMotor
RX72T(R5F572TKCDFB)24V inverter board & RX72T CPU Card (Note 1)FH6S20E-X81 (Note 2)
Toolchain version
CC-RX V3.01.00

For purchase and technical support, contact sales representatives and dealers of Renesas Electronics Corporation.

Notes: 1. 24V inverter board & RX72T CPU Card are products of Renesas Electronics Corporation. 2. FH6S20E-X81 is a product of NIDEC SERVO CORPORATION. NIDEC SERVO (http://www.nidec-servo.com/)

2. System overview

The system overview is explained below.

2.1 Hardware configuration

The hardware configuration is shown below.

Figure 2-1 Hardware Configuration Diagram: This diagram illustrates the connection of the RX72T microcontroller to an inverter circuit and a Permanent Magnet Synchronous Motor (PMSM). The RX72T receives inputs for bus voltage (IU_AIN, IW_AIN), phase currents (IU, IW), and a rotation speed command. It outputs PWM signals (Up, Vp, Wp, Un, Vn, Wn) to the inverter circuit. The inverter circuit drives the PMSM. The diagram also shows connections for switches (START/STOP, ERROR RESET), LEDs, over-current detection input (P70/POE0#), and encoder inputs (PA7/MTCLKA, PA6/MTCLKB). A power supply circuit provides DC 24V.

2.2 Hardware specifications

2.2.1 User interfaces

The user interfaces of this system are given in Table 2-1.

ItemInterface componentFunction
Rotation position / speedVariable resistor (VR1)Reference value of rotation position / speed input (analog value)
START/STOPToggle switch (SW1)Motor rotation start/stop command
ERROR RESETToggle switch (SW2)Command of recovery from error status
LED1Yellow green LED- At the time of motor rotation: ON
- At the time of stop: OFF
LED2Yellow green LED- At the time of error detection: ON
- At the time of normal operation: OFF
LED3Yellow green LED- Complete of positioning: ON
- Uncomplete of positioning: OFF
RESETPush switchSystem reset

The port interfaces of this system are given in Table 2-2.

R5F572TKCDFB port nameFunction
P63 / AN209Inverter bus voltage measurement
P43 / AN003For position / speed command value input (analog value)
P35START/STOP toggle switch
PA0ERROR RESET toggle switch
PC5LED1 ON/OFF control
PC6LED2 ON/OFF control
P34LED3 ON/OFF control
P40 / AN000U phase current measurement
P42 / AN002W phase current measurement
P71 / MTIOC3B / GTIOC4APWM output (Up)
P72 / MTIOC4A / GTIOC5APWM output (Vp)
P73 / MTIOC4B / GTIOC6APWM output (Wp)
P74 / MTIOC3D / GTIOC4BPWM output (Un)
P75 / MTIOC4C / GTIOC5BPWM output (Vn)
P76 / MTIOC4D / GTIOC6BPWM output (Wn)
P23 / IRQ11Hall Phase-U signal input
P24 / IRQ4Hall Phase-V signal input
P25 / IRQ10Hall Phase-W signal input
PA7 / MTCLKAEncoder Phase-A signal input
PA6 / MTCLKBEncoder Phase-B signal input
P70 / POE0#PWM emergency stop input at the time of over-current detection

2.2.2 Peripheral functions

The peripheral functions used in this system are given in Table 2-3.

12-bit A/DCMTMTU3 / GPTWPOE3B
- Rotation speed command value input
- Current of each phase U and W measurement
- Inverter bus voltage measurement
500 [µs] interval timer- Complementary PWM output
- Encoder phase counter
- Encoder count capture
Set PWM output ports to high impedance state to stop the PWM output.

(1) 12-bit A/D converter (S12ADH)
U phase current (Iu), W phase current (Iw), inverter bus voltage (Vdc) and rotation speed reference are measured by using the single scan mode (use hardware trigger). The sample-and-hold function is used for U phase current (Iu) and W phase current (Iw) measurement.

(2) Compare match timer (CMT)
The channel 0 of the compare match timer is used as a 500 [µs] interval timer.

(3) Multi-function timer pulse unit 3 (MTU3d)
The operation mode varies depending on channels. On channels 3 and 4, output (active level: high) with dead time is performed using the complementary PWM mode. The channel 1 of MTU3 operates in phase counting mode, where the counter is incremented or decremented according to the phase difference between Phase-A and Phase-B signals from the encoder.

(4) General PWM Timer (GPTW)
The operation mode varies depending on channels. On channels 4, 5, and 6, output (active level: high) with dead time is performed using the PWM Output Operating mode. The channel 3 operates in phase counting mode, where the counter is incremented or decremented according to the phase difference between Phase-A and Phase-B signals from the encoder. The channel 9 is used as a free-run timer for speed measurement.

(5) Port output enable 3 (POE3B)
PWM output ports are set to high impedance state when an overcurrent is detected (when a falling edge of the POE0# port is detected) and when an output short circuit is detected.

The setting of the PWM output timer is selected by the following macro definition.

File nameMacro nameDefinition valueRemarks
r_mtr_ctrl_rx72t.hMTR_GPT00:MTU
1:GPT

2.3 Software configuration

2.3.1 Software file configuration

The folder and file configuration of the sample programs are given below.

Figure 2-2 Folder and file configuration: This diagram shows the hierarchical structure of the software project files for the motor control application. It is organized into layers: `application` (main, user_interface, ics, board), `middle` (interface, common, control, inverter, mcu, sensor), and `config`. Each folder contains specific `.h` and `.c` files or libraries, with brief descriptions of their functions (e.g., `main.c` for main function, `r_mtr_pi_control.c` for PI controller function definition).

Notes: 1. Regarding the specification of Analyzer function in the motor control development support tool 'Renesas Motor Workbench', please refer to Chapter 4. The identifier 'ics/ICS' (ICS is the previous motor control development support tool ‘In Circuit Scope') is attached to the names of folders, files, functions, and variables related to 'Renesas Motor Workbench'.

2.3.2 Module configuration

The module configuration of the sample programs is described below.

Figure 2-3 Module Configuration: This diagram visually represents the software module architecture. It shows three main layers: `Application Layer` (User Application), `Middle Layer` (Motor Control Process), and `Device Layer` (MCU Register Access, Inverter Driver, Sensor Driver), with the `H/W Layer` at the bottom. Data flow and function calls between modules like `main.c`, `r_mtr_driver_access.c`, `r_mtr_interrupt_carrier.c`, `r_mtr_foc_current.c`, `r_mtr_ctrl_encoder.c`, and `r_mtr_ctrl_rx72t.c` are depicted.

2.4 Software specifications

Table 2-5 shows the basic software specifications of this system. For details of the vector control, refer to the application note 'Vector control of permanent magnet synchronous motor with encoder: algorithm'.

ItemContent
Control methodVector control
Motor control start/stopDetermined depending on the level of SW1 ("Low": control start, "High": stop) or input from Analyzer
Position detection of rotor magnetic poleIncremental encoder (A-B Phase), Hall sensor (UVW Phase)
Input voltageDC 24 [V]
Carrier frequency (PWM)20 [kHz] (carrier cycle: 50[µs])
Dead time2 [µs]
Control cycle (Current loop)50 [µs]
Control cycle (Speed and Position loop)500 [µs]
Management of position command valueBoard UI: Position command generation: Direct input of VR1 (input range) -180°~180°
ICS UI: Position command generation: Position profile of trapezoidal curve for speed command value (input range) -32768°~32767° (Max speed)
Management of speed command valueCW / CCW: 2000[rpm]
Accuracy of position0.3° (Encoder pulse: 300[ppr] / 4 for multiplying 1200[cpr])
Dead band of position (Note)Encoder count ±1 [cpr] (±0.3°)
Natural frequency of each control systemCurrent control system:300Hz
Speed control system:30Hz
Position control system:10Hz
Optimization setting for compilerOptimization level: 2 (-optimize=2) (default)
Optimization method: Size priority (default)
ROM/RAM sizeROM: 21.0KB
RAM: 4.8KB
Processing stop for protectionMotor control signal outputs (six outputs) will be disabled under any of the following conditions:
1. Current of each phase exceeds 3.28 [A] (monitored every 50 [µs])
2. Inverter bus voltage exceeds 28 [V] (monitored every 50 [µs])
3. Inverter bus voltage is less than 14 [V] (monitored every 50 [µs])
4. Rotation speed exceeds 3000 [rpm] (monitored every 50 [µs])
When an external over current signal is detected (when a falling edge of the POE0# port is detected) and when the output short circuit is detected, the PWM output ports are set to high impedance state.

Note: Dead zone is provided to prevent hunting in positioning.

3. Descriptions of the Control Program

The target sample programs of this application note are explained here.

3.1 Contents of Control

3.1.1 Motor Start/Stop

The start and stop of the motor are controlled by input from the Analyzer function of ‘Renesas Motor Workbench' or the SW1 switch of the RSSK board. A general-purpose port is assigned to SW1. The port is read within the main loop. When the port is at a 'Low' level, the software determines that the motor should be started. Conversely, when the level is switched to 'High', the program determines that the motor should be stopped.

3.1.2 A/D Converter

(1) Motor Rotation Position and Speed Command Value

The motor rotation position and speed command value can be set by Analyzer input or A/D conversion of the VR1 output value (analog value). The A/D converted VR1 value is used as the rotation speed command value, as shown below.

ItemConversion ratio (Command value: A/D conversion value)Channel
Rotation position command valueCW: 0°~180°:0800H~0FFFH
CCW: 0°~-180°:07FFH~0000H
AN003
Rotation speed command valueCW: 0 [rpm]~2000[rpm]:0800H~0FFFH
CCW: 0 [rpm]~2000[rpm]:07FFH~0000H
(2) Inverter Bus Voltage

Inverter bus voltage is measured as given in the documentation. It is used for modulation factor calculation, under-voltage detection, and over-voltage detection. (When an abnormality is detected, PWM is stopped.)

ItemConversion ratio (Inverter bus voltage: A/D conversion value)Channel
Inverter bus voltage0 [V] to 111 [V]: 0000H to 0FFFHAN209
(3) U, W Phase Current

The U and W phase currents are measured as shown in the documentation and used for vector control.

ItemConversion ratio (U, W phase current: A/D conversion value)Channel
U, W phase current-10 [A] to 10 [A]: 0000H to 0FFFH (Note 1)Iu: AN000
Iw: AN002

Notes: 1. For more details of A/D conversion characteristics, refer to RX72T Group User's Manual: Hardware.

3.1.3 Position Profile Generation

(Position Profile of Trapezoidal Curve for Speed Command Value)

In vector control software for PMSM with encoder, position profile generation is used to create the command value (input position value). The implementation uses each control cycle to manage acceleration and maximum speed relative to the target position value.

Figure 3-1 Position Profile Generation: This graph illustrates the generation of a position command profile, typically a trapezoidal curve for speed. It shows how speed and position change over time. Key variables like com_s2_ref_position_deg (target position), com_f4_accel_time (acceleration time), and com_s2_max_speed_rpm (maximum speed) are used to define the profile.

Enter the following variables from the Analyzer to create a command value:

  • Position reference [degree] (com_s2_ref_position_deg)
  • Acceleration time (com_f4_accel_time)
  • Maximum speed command value (com_f4_accel_max_ref_speed_rad)
  • Position stabilization wait time (com_u2_ref_pos_interval_time)

3.1.4 Speed Measurement

To achieve better real-time performance and higher speed resolution at low speeds, this system uses the encoder signal edge interval to calculate speed. Speed extrapolation is used in PI control calculation. Considering the difference between rise and fall times and the accuracy of the encoder signal's quadrature, speed is calculated based on elapsed time and angle change over one period of the encoder's Phase-A or Phase-B signals.

(1) Speed Calculation

Figure 3-2 Speed Calculation using Encoder: This diagram explains how motor speed is calculated using encoder signals. It shows Phase A and Phase B encoder signals, a timer counter, and the formula: Motor Rotation Speed[rad/s] = (Count Per Rotation / Timer Clock Frequency) / (Counter Difference). It highlights capture points on the encoder signals.

3.1.5 Modulation

The target software of this application note uses pulse width modulation (PWM) to generate the input voltage to the motor. The PWM waveform is generated by the triangular wave comparison method.

(1) Triangular Wave Comparison Method

The triangular wave comparison method is used to output the voltage command value. The pulse width of the output voltage is determined by comparing the carrier waveform (triangular wave) with the voltage command value waveform. The voltage command value of the pseudo sinusoidal wave is output by turning the switch on or off when the voltage command value is larger or smaller than the carrier wave, respectively.

Figure 3-3 Conceptual Diagram of the Triangular Wave Comparison Method: This figure visually explains the PWM generation process. It shows three sinusoidal modulation waves (U, V, W) representing voltage commands, and a triangular carrier wave. The PWM output waveforms for each phase (U, V, W) are generated by comparing the modulation waves with the carrier wave. The voltage between two phases (e.g., U-V) is also depicted.

Figure 3-4 Definition of Duty: This diagram defines the duty cycle of a PWM signal. It shows a single PWM pulse with ON time (TON) and OFF time (TOFF) within a period (TON + TOFF). The formula Duty = (TON / (TON + TOFF)) * 100 [%] is provided. It also shows how the average voltage relates to the duty cycle.

Modulation factor m is defined as follows:

m = V / E

where: m: Modulation factor, V: Voltage command value, E: Inverter bus voltage.

The voltage command can be generated by setting the PWM compare register properly to obtain the desired duty.

3.1.6 State Transition

Figure 3-5 State Transition Diagram of Vector Control PMSM with Encoder Software: This diagram illustrates the operational states of the motor control software. It shows transitions between SYSTEM MODE states (INACTIVE, ACTIVE, ERROR) triggered by EVENTs (user operation, error detection). It also shows RUN MODE states (INIT, BOOT, DRIVE) and how Control Config (Current, Speed, Position, Torque, Voltage) changes.

The software state is managed by ‘SYSTEM MODE' and ‘RUN MODE'. 'Control Config' shows the active control system.

  • (1). SYSTEM MODE: Indicates the operating states of the system. Transitions occur based on events. It has three states: motor drive stop (INACTIVE), motor drive (ACTIVE), and abnormal condition (ERROR).
  • (2). RUN MODE: Indicates the condition of the motor control. It transitions sequentially when 'SYSTEM MODE' is 'ACTIVE'.
  • (3). EVENT: When an 'EVENT' occurs in each 'SYSTEM MODE', the 'SYSTEM MODE' changes as shown in the table below.
EVENT nameOccurrence factor
INACTIVEby user operation
ACTIVEby user operation
ERRORwhen the system detects an error
RESETby user operation

3.1.7 Startup Method

Figure 3-6 Startup Position Control of Vector Control PMSM with Encoder Software: This graph depicts the sequence of operations during the startup phase for position control. It shows how Id reference, Iq reference, speed reference, and position reference change over time as the system transitions through MTR_MODE_INIT, MTR_MODE_BOOT, and MTR_MODE_DRIVE.

Figure 3-7 Startup Speed Control of Vector Control PMSM with Encoder Software: Similar to Figure 3-6, this graph illustrates the startup sequence for speed control, showing how Id reference, Iq reference, and speed reference evolve during initialization, boot, and drive modes.

This section shows the software implementation of d-axis and encoder alignment methods. The d-axis alignment method is used as startup control for position control, in initialization mode (MTR_MODE_INIT) and Boot mode (MTR_MODE_BOOT). In drive mode (MTR_MODE_DRIVE), vector control is implemented for PMSM with Encoder. Each reference value setting of d-axis current, q-axis current, and speed is managed by respective status.

For details of the position control of a vector-controlled PMSM using an encoder, refer to the application note ‘Vector control of permanent magnet synchronous motor with encoder: algorithm'.

3.1.8 System Protection Function

This control program includes the following error statuses and executes emergency stop functions in case of respective errors. Table 3-4 shows the setting values for the system protection function.

  • Over-current error: Detected by both hardware and software methods. An emergency stop signal from hardware (detection) sets PWM output ports to high impedance state. U, V, and W phase currents are monitored. The CPU executes an emergency stop (software detection) if an over-current is detected. The limit is calculated from the nominal motor current [MP_NOMINAL_CURRENT_RMS].
  • Over-voltage error: Inverter bus voltage is monitored. The CPU performs an emergency stop upon detecting over-voltage, considering resistance errors in the detection circuit.
  • Under-voltage error: Inverter bus voltage is monitored. The CPU performs an emergency stop upon detecting under-voltage, considering resistance errors in the detection circuit.
  • Over-speed error: Rotation speed is monitored. The CPU performs an emergency stop if the speed exceeds the limit value.
Over-current limit value [A]Monitoring cycle [µs]Over-voltage limit value [V]Monitoring cycle [µs]Under-voltage limit value [V]Monitoring cycle [µs]Speed limit value [rpm]Monitoring cycle [µs]
3.825028501450300050

3.2 Function Specifications of Vector Control using Encoder Software

The control process of the target software is mainly composed of 50[µs] period interrupts (carrier interrupt) and 500[µs] period interrupts. The red broken line parts in Figure 3-8 are executed every 50[µs] period, and the blue broken line parts are executed every 500[µs] period.

Figure 3-8 System Block of Vector Control with Encoder: This is a high-level block diagram of the entire vector control system. It shows the interaction between different interrupt processes (Carrier Interrupt, 500us Interrupt, Hall Interrupt, Encoder Interrupt) and control loops (Position/Speed Loop, Current PI, Decoupling Control, etc.). It highlights the flow of data such as references, currents, voltages, and rotor angle.

This chapter details 4 interrupt functions and functions executed in each interrupt cycle. Essential functions for vector control are listed in the following tables; refer to source codes for specifications of unlisted functions.

File nameFunction nameProcess overview
r_mtr_interrupt_carrier.cmtr_foc_carrier_interruptCalling every 50 [µs]
- Current and voltage monitoring
- Error detection
- Current offset detection
- Vector calculation
- Current PI control
r_mtr_interrupt_timer.cmtr_foc_500us_interruptCalling every 500 [µs]
- Startup control
- d-axis/q-axis current and speed reference set
- Speed PI control
r_mtr_interrupt_sensor.cmtr_angle_adj_hall_interruptCalled when Hall phase signals (Phase-U/V/W) are received
- Get Hall signal
- Rotor phase calculation
- Hall error process
- Disable Hall interrupt
mtr_encd_pos_speed_calc_interruptCalled when encoder phase counts (Phase-A and B) are received
- Rotor phase calculation
- Speed calculation
File nameFunction nameProcess overview
r_mtr_ctrl_mrssk.cmtr_get_current_iuiw
mtr_get_vdc
Obtaining the UVW phase current
Obtaining the Vdc
r_mtr_foc_control_encd_position.cmtr_error_check
mtr_current_offset_adjustment
mtr_calib_current_offset
mtr_encd_pos_speed_calc
Error monitoring
UVW phase current offset adjustment
UVW phase current offset calculation
Position and speed calculation for encoder pulse
r_mtr_foc_current.cmtr_foc_voltage_limitVoltage command value limit
r_mtr_transform.cmtr_angle_speed
mtr_current_pi_control
mtr_decoupling_control
mtr_transform_uvw_dq_abs
mtr_transform_dq_uvw_abs
Rotor phase and speed related process (Switching calculation method)
Current PI
Decoupling control
Coordinate transform UVW to dq
Coordinate transform dq to UVW
File nameFunction nameProcess overview
r_mtr_volt_err_comp.cmtr_volt_err_comp_mainVoltage error compensation
r_mtr_ctrl_rx72t.cmtr_inv_set_uvwPWM output setting
File nameFunction nameProcess overview
r_mtr_ctrl_hall.cmtr_angle_adj_hall_initInitialize rotor angle detection for Hall sensor
r_mtr_ctrl_encoder.cmtr_set_encd_tcnt
mtr_encd_cnt_reset
mtr_speed_calc_timer_start
mtr_irq_interrupt_enable
Set for encoder count register
Initialize encoder timer counter value
Start for encoder timer
Enable Hall interrupt
r_mtr_foc_control_encd_position.cmtr_hall_error
mtr_set_pos_ref
mtr_set_speed_ref
mtr_set_iq_ref
mtr_set_id_ref
Hall sensor error process
Setting the command value for position control
Setting the command value for speed control
Setting the q-axis current command value
Setting the d-axis current command value
r_mtr_fluxwkn.objR_FLUXWKN_RunFlux-weakening control

3.3 Macro Definitions of Vector Control Software Using Encoder

Lists of macro definitions used in this control program are given below.

File nameMacro nameDefinition valueRemarks
r_mtr_motor_parameter.hMP_POLE_PAIRS
MP_MAGNETIC_FLUX
MP_RESISTANCE
MP_D_INDUCTANCE
MP_Q_INDUCTANCE
MP_ROTOR_INERTIA
MP_NOMINAL_CURRENT_RMS
7
0.006198f
0.453f
0.0009447f
0.0009447f
0.00000962f
1.8f
Number of pole pairs
Flux [Wb]
Resistance [Ω]
d-axis Inductance [H]
q-axis Inductance [H]
Rotor inertia [kgm^2]
Nominal torque [Arms]
File nameMacro nameDefinition valueRemarks
r_mtr_control_parameter.hCP_CURRENT_OMEGA
CP_CURRENT_ZETA
CP_SPEED_OMEGA
CP_SPEED_ZETA
CP_POS_OMEGA
CP_SOB_OMEGA
CP_SOB_ZETA
CP_MIN_SPEED_RPM
CP_MAX_SPEED_RPM
CP_SPEED_LIMIT_RPM
CP_OL_ID_REF
300.0f
1.0f
30.0f
1.0f
10.0f
200.0f
1.0f
0
2000
3000
1.5f
Natural frequency of the current loop[Hz]
Damping ratio of the current loop
Natural frequency of the speed loop[Hz]
Damping ratio of the speed loop
Natural frequency of the position loop[Hz]
Natural frequency of the speed observer[Hz]
Damping ratio of the speed observer
Minimum speed (mechanical) [rpm]
Maximum speed (mechanical) [rpm]
Limit speed (mechanical) [rpm]
d-axis current command value [A]
File nameMacro nameDefinition valueRemarks
r_mtr_inverter_parameter.hIP_DEADTIME
IP_CURRENT_RANGE
IP_VDC_RANGE
IP_INPUT_V
IP_CURRENT_LIMIT
IP_OVERVOLTAGE_LIMIT
IP_UNDERVOLTAGE_LIMIT
2.0f
20.0f
111.0f
24.0f
5.0f
28.0f
14.0f
Deadtime [µs]
current sensing range
voltage sensing range
input DC voltage [V]
Current limit[A] (Note)
Over voltage limit [V]
Under voltage limit [V]

Note: This value is calculated from the rated power of the shunt resistance.

File nameMacro nameDefinition valueRemarks
r_mtr_config.hIP_MRSSK
RX72T_MRSSK
MP_FH6S20EX81
CP_FH6S20EX81
RP_FH6S20EX81
CONFIG_DEFAULT_UI
-Inverter select macro
MCU select macro
Motor select macro
Select default UI
ICS_UI: Use the Analyzer for RMW
BOARD_UI: Use board interface
FUNC_ON
FUNC_OFF
DEFAULT_FLUX_WEAKENI NG
DEFAULT_VOLT_ERR_CO MP
ANGLE_ADJUST_MODE
1
0
FUNC_OFF
FUNC_ON
MTR_ANGLE_ADJ_EXCIT
Enable
Disable
Flux weakening control
Voltage error compensation
Select angle adjust mode
MTR_ANGLE_ADJ_EXCIT: Forced excitation mode
MTR_ANGLE_ADJ_HALL: Hall mode
POS_CTRL_MODE
LOOP_MODE
GAIN_MODE
MOD_METHOD
MTR_CTRL_IPD
MTR_LOOP_POSITION
MTR_GAIN_DESIGN_MODE
MOD_METHOD_SVPWM
Select position control mode
MTR_CTRL_PID: PID controller
MTR_CTRL_IPD: IPD controller
Select control loop mode
MTR_LOOP_SPEED: speed loop
MTR_LOOP_POSITION: position loop
Gain mode
MTR_GAIN_DESIGN_MODE: PI gain design mode
MTR_GAIN_DIRECT_MODE: PI gain direct input mode
modulation method
MOD_METHOD_SPWM: Sinusoidal PWM
MOD_METHOD_SVPWM: Space Vector PWM
File nameMacro nameDefinition valueRemarks
r_mtr_encoder_parameter.hEP_PULSE_PER_REV300Pulse per revolution [ppr]
File nameMacro nameDefinition valueRemarks
r_mtr_common.hMTR_TFU_OPTIMIZE11:Use TFU code
0:Use Standard library code

3.4 Control Flowcharts

3.4.1 Main Process

Figure 3-9 Main Process Flowchart: This flowchart outlines the main execution sequence of the control program. It includes initialization steps for peripherals, user interface, variables, sequence process, and Analyzer. It also shows the power supply stabilization wait, decision points for Analyzer vs. Board UI, parameter input, motor operation mode changes, LED control, and watchdog timer clearing.

3.4.2 Carrier Synchronous Interrupt Handling (Vector Control using Encoder)

Figure 3-10 50 [µs] Cycle Interrupt Handling: This flowchart details the steps executed within the 50-microsecond interrupt service routine. It covers encoder counter processing, current and voltage acquisition, error checks, offset adjustments, coordinate transformations (UVW to dq), current PI control, decoupling control, voltage limiting, phase-lead compensation, and PWM duty calculation.

3.4.3 500 [µs] Interrupt Handling

Figure 3-11 500 [µs] Interrupt Handling: This flowchart describes the actions taken during the 500-microsecond interrupt. It includes decisions based on SYSTEM MODE (INACTIVE, ACTIVE) and RUN MODE (INIT, BOOT, DRIVE), handling Hall and encoder signals, setting various references (position, speed, current), and managing state transitions.

3.4.4 Over Current Detection Interrupt Handling

Figure 3-12 Over Current Detection Interrupt Handling: This flowchart shows the process when an over-current condition is detected. It leads to a motor stop process and clearing of high-impedance status.

3.4.5 Encoder Count Capture Interrupt Handling

Figure 3-13 Encoder Count Capture Interrupt Handling: This flowchart illustrates the steps performed upon an encoder count capture interrupt. It includes checking if encoder alignment is finished, accumulating encoder counts, calculating position, detecting zero speed, and calculating speed.

3.4.6 Hall Signal Interrupt Handling

Figure 3-14 Hall Signal Interrupt Handling: This flowchart details the handling of Hall sensor signals. It shows detection of Hall signals, calculation of rotor angle, error handling, and disabling the Hall interrupt, depending on the RUN MODE.

4. Motor Control Development Support Tool ‘Renesas Motor Workbench’

4.1 Overview

‘Renesas Motor Workbench' is a support tool for motor control system development. It can be used with the target software of this application note to analyze control performance. The user interfaces provide functions like rotating/stop command and setting rotation speed reference. Refer to the ‘Renesas Motor Workbench User's Manual' for usage and more details. ‘Renesas Motor Workbench' can be downloaded from the Renesas Electronics Corporation website.

Figure 4-1 Renesas Motor Workbench – Appearance: This figure shows screenshots of the Renesas Motor Workbench software. It displays the "Main Window" with options for file management, connection, and configuration, and the "Analyzer Window" which includes controls for commander, scope, variables, and data acquisition.

Set up for ‘Renesas Motor Workbench’

  1. Start 'Renesas Motor Workbench' by clicking its icon.
  2. Click on [File] and select [Open RMT File(O)] from the drop-down Menu. Select the RMT file from the following location of the e2studio/CS+ project folder: '[Project Folder]/application/user_interface/ics/'.
  3. Use the 'Connection' [COM] select menu to choose the COM port.
  4. Click on the 'Analyzer' icon in the Select Tool panel to open the Analyzer function window.
  5. Refer to '4.3 Operation Example for Analyzer' for motor driving operation.

4.2 List of Variables for Scope Function 'Analyzer'

Table 4-1 is a list of variables for the Analyzer. These variable values are reflected to the protect variables when the same values as g_u1_enable_write are written to com_u1_enable_write. Variables with (*) do not depend on com_u1_enable_write.

Variable nameTypeContent
com_u1_sw_userif (*)uint8_tUser interface switch
0: ICS user interface use (default)
1: Board user interface use
com_u1_mode_system(*)uint8_tState management
0: Stop mode
1: Run mode
3: Reset
com_u1_directionuint8_tRotation direction
0: CW
1: CCW
com_u1_ctrl_loop_modeuint8_tControl loop mode switch
0: Speed control
1: Position control (default)
com_u1_ctrl_method_modeuint8_tControl method switch
0: PID control (Position P/Speed PI/Current PI)
1: IPD control (position Speed IPD +Position FF+ Speed FF+Position P/ Current PI) (default)
FF: Feed-forward control
com_u1_position_input_modeuint8_tPosition reference input mode switch
0: 0 output
1: Direct input
2: Position profiling (default)
com_u1_encd_angle_adj_modeuint8_tAngle detection mode switch
0: Forced excitation (default)
1: Position detection using Hall signal
com_s2_ref_position_degint16_tPosition command value [degree]
com_s2_ref_speed_rpmint16_tSpeed command value [rpm]
com_u2_min_speed_rpmuint16_tMinimum speed [[rpm]
com_u2_max_speed_rpmuint16_tMaximum speed [rpm]
com_u2_speed_limit_rpmuint16_tOverspeed Limit [rpm]
com_u2_hs_change_speed_rpmuint16_tSpeed calculation mode switch speed [rpm]
com_u2_hs_change_margin_rpmuint16_tSpeed calculation mode switch margin speed [rpm]
com_u2_pos_interval_timeuint16_tTime interval of the position command changes [s]
com_u2_pos_dead_banduint16_tDead band of position
com_u2_pos_band_limituint16_tPositioning complete range
com_u2_encd_cpruint16_tEncoder pulse count (4 for multiplying)
com_u2_offset_calc_timeuint16_tCurrent offset value calculation time [ms]
com_u2_mtr_ppuint16_tNumber of pole pairs
com_f4_mtr_rfloatResistance [Ω]
com_f4_mtr_ldfloatd-axis Inductance [H]
com_f4_mtr_lqfloatq-axis Inductance [H]
com_f4_mtr_mfloatFlux [Wb]
com_f4_mtr_jfloatInertia [kgm^2]
com_f4_nominal_current_rmsfloatNominal current [Arms]
Variable nameTypeContent
com_f4_current_omegafloatNatural frequency of the current loop[Hz]
com_f4_current_zetafloatDamping ratio of the current loop
com_f4_speed_omegafloatNatural frequency of the speed loop[Hz]
com_f4_speed_zetafloatDamping ratio of the speed loop
com_f4_pos_omegafloatNatural frequency of the position loop[Hz]
com_f4_sob_omegafloatNatural frequency of the speed observer [Hz]
com_f4_sob_zetafloatDamping ratio of the speed observer
com_f4_id_kpfloatd-axis current PI control proportional term gain
com_f4_id_kifloatd-axis current PI control integral term gain
com_f4_iq_kpfloatq-axis current PI control proportional term gain
com_f4_iq_kifloatq-axis current PI control integral term gain
com_f4_speed_kpfloatSpeed PI control proportional term gain
com_f4_speed_kifloatSpeed PI control integral term gain
com_f4_pos_kpfloatPosition control proportional term gain
com_f4_ipd_speed_k_ratiofloatSpeed control gain ratio for IPD
com_f4_ipd_pos_kp_ratiofloatPosition control proportional term gain ratio for IPD
com_f4_ipd_err_limit_1floatPosition error limit for IPD
com_f4_ipd_err_limit_2floatPosition error limit for IPD
com_f4_accel_timefloatAcceleration time [s] (for position control)
com_f4_ol_ref_idfloatd-axis current command value [A]
com_f4_id_up_timefloatd-axis current command value addition time [ms]
com_f4_speed_rate_limitfloatAcceleration limit [s] (for speed control)
com_u1_enable_writeuint8_tEnabled to rewriting variables
Name of primary variable for Encoder Vector ControlTypeContent
g_st_foc.u2_error_statusuint16_terror status
g_st_foc.st_cc.f4_id_reffloatd-axis current command value [A]
g_st_foc.st_cc.f4_id_adfloatd-axis current [A]
g_st_foc.st_cc.f4_iq_reffloatq-axis current command value [A]
g_st_foc.st_cc.f4_iq_adfloatq-axis current [A]
g_st_foc.f4_iu_adfloatU phase current A/D conversion value [A]
g_st_foc.f4_iv_adfloatV phase current A/D conversion value [A]
g_st_foc.f4_iw_adfloatW phase current A/D conversion value [A]
g_st_foc.st_cc.f4_vd_reffloatd-axis output voltage command value [V]
g_st_foc.st_cc.f4_vq_reffloatq-axis output voltage command value [V]
g_st_foc.f4_refufloatU phase voltage command value [V]
g_st_foc.f4_refvfloatV phase voltage command value [V]
g_st_foc.f4_refwfloatW phase voltage command value [V]
g_st_foc.st_sc.f4_ref_speed_rad_ctrlfloatCommand value for speed PI control (Electrical) [rad/s]
g_st_foc.st_sc.f4_speed_radfloatSpeed (Electrical) [rad/s]
g_st_foc.st_pc.f4_ref_pos_rad_ctrlfloatCommand value for Position control (Electrical) [rad]
g_st_foc.st_pc.f4_pos_radfloatPosition (Electrical) [rad]

4.3 Operation Example for Analyzer

This section provides an example of motor driving operation using the Analyzer's 'Control Window'. Refer to the 'Renesas Motor Workbench User's Manual' for specifications of the 'Control Window'.

- Driving the motor

  1. Confirm the check-boxes in the [W?] column for 'com_u1_mode_system', 'com_s2_ref_speed_rpm', and 'com_u1_enable_write'.
  2. Input a reference speed value in the [Write] box of 'com_s2_ref_speed_rpm'.
  3. Click the 'Write' button.
  4. Click the 'Read' button. Confirm the [Read] box values for 'com_s2_ref_speed_rpm' and 'g_u1_enable_write'.
  5. Set the same value as 'g_u1_enable_write' in the [Write] box of 'com_u1_enable_write'.
  6. Write '1' in the [Write] box of 'com_u1_mode_system'.
  7. Click the 'Write' button.

Figure 4-2 Procedure - Driving the motor: This figure illustrates the steps for driving the motor using the Analyzer. It shows UI elements like the 'Read' and 'Write' buttons, check boxes, and input fields for variables.

- Stop the motor

  1. Write '0' in the [Write] box of 'com_u1_mode_system'.
  2. Click the 'Write' button.

Figure 4-3 Procedure - Stop the motor: This figure shows the steps to stop the motor by setting the 'com_u1_mode_system' variable to '0' and clicking 'Write'.

- Error cancel operation

  1. Write '3' in the [Write] box of 'com_u1_mode_system'.
  2. Click the 'Write' button.

Figure 4-4 Procedure - Error cancel operation: This figure illustrates how to cancel an error by setting the 'com_u1_mode_system' variable to '3' and clicking 'Write'.

4.4 Operation Example for User Button

This section provides examples of motor driving operations using the User Button.

- Driving or Stop the motor in position control mode
By setting as shown in Figure 4-5, driving and stopping change each time the button is pressed.

Figure 4-5 Driving or Stop the Motor in position control mode: This figure shows the User Button interface for controlling the motor in position control mode, illustrating how button presses toggle between start/stop states.

- Change position
By setting as shown in Figure 4-6, enter the command position and press the button to change the position.

Figure 4-6 Change position: This figure displays the User Button interface for changing the motor's position, showing how to input a 'Position Reference' value and trigger the update.

- Driving or Stop the motor in speed control mode
By setting as shown in Figure 4-7, driving and stopping change each time the button is pressed.

Figure 4-7 Driving or Stop the Motor in speed control mode: This figure shows the User Button interface for controlling the motor in speed control mode, illustrating how button presses toggle between start/stop states.

- Change speed
By setting as shown in Figure 4-8, enter the command speed and press the button to change the speed.

Figure 4-8 Change speed: This figure displays the User Button interface for changing the motor's speed, showing how to input a 'Speed Reference' value and trigger the update.

Website and Support

Renesas Electronics Website: http://www.renesas.com/

Inquiries: http://www.renesas.com/contact/

All trademarks and registered trademarks are the property of their respective owners.

Revision History

Rev.DatePageDescription Summary
1.00Mar. 29, 2019-First edition issued

General Precautions in the Handling of Microprocessing Unit and Microcontroller Unit Products

The following usage notes are applicable to all Microprocessing unit and Microcontroller unit products from Renesas. For detailed usage notes on the products covered by this document, refer to the relevant sections of the document as well as any technical updates that have been issued for the products.

  1. Precaution against Electrostatic Discharge (ESD): A strong electrical field can cause destruction of the gate oxide and degrade device operation. Steps must be taken to stop static electricity generation and dissipate it quickly. Environmental control, including humidifiers in dry conditions, is recommended. Avoid insulators that build up static electricity. Store and transport semiconductor devices in anti-static containers or shielding bags. Ground all test equipment, workbenches, and floors. Operators must use wrist straps. Do not touch semiconductor devices with bare hands. Similar precautions apply to printed circuit boards with mounted devices.
  2. Processing at power-on: Product state is undefined when power is supplied. Internal circuit states, register settings, and pin states are indeterminate. For products with external reset pins, pin states are not guaranteed until the reset process is complete. For products with on-chip power-on reset, pin states are not guaranteed until the power reaches the specified reset level.
  3. Input of signal during power-off state: Do not input signals or use I/O pull-up power supplies while the device is powered off. Such inputs can cause malfunction and abnormal current, potentially degrading internal elements. Follow product documentation guidelines for power-off state signal input.
  4. Handling of unused pins: Handle unused pins according to manual directions. CMOS product input pins are generally in a high-impedance state. Open-circuit operation can induce electromagnetic noise, cause shoot-through current, and lead to malfunctions due to false pin state recognition.
  5. Clock signals: After reset, release the reset line only after the operating clock signal is stable. When switching clock signals during program execution, wait for stabilization. If the clock signal is generated externally during reset, ensure the reset line is released only after full stabilization.
  6. Voltage application waveform at input pin: Waveform distortion due to noise or reflected waves can cause malfunction. If the input level stays between VIL (Max.) and VIH (Min.) due to noise, malfunction may occur. Prevent chattering noise and manage transition periods carefully.
  7. Prohibition of access to reserved addresses: Access to reserved addresses is prohibited as they are for future function expansion. Accessing them may lead to incorrect LSI operation.
  8. Differences between products: Before changing products (e.g., different part numbers), confirm that the change will not cause problems. Differences in memory capacity or layout can affect electrical characteristics. System evaluation tests are necessary when changing part numbers.

Notice

1. Circuit, software, and information descriptions are for illustration and application examples only. Users are responsible for the incorporation and use of these in their products. Renesas Electronics disclaims liability for losses or damages from their use.

2. Renesas Electronics disclaims warranties against infringement of third-party intellectual property rights arising from the use of its products or technical information.

3. No license is granted under any patents, copyrights, or other intellectual property rights of Renesas Electronics or others.

4. Altering, modifying, copying, or reverse engineering Renesas Electronics products is prohibited. Renesas Electronics disclaims liability for damages from such actions.

5. Renesas Electronics products are classified as "Standard" or "High Quality" based on intended applications. "Standard" is for general equipment, while "High Quality" is for transportation, traffic control, and safety-critical systems. Renesas Electronics products are not intended for use in systems that pose a direct threat to human life or cause serious property damage unless expressly designated for high reliability or harsh environments. Renesas Electronics disclaims liability for damages from use inconsistent with data sheets or user manuals.

6. When using Renesas Electronics products, refer to the latest product information (data sheets, user's manuals, application notes, etc.) and ensure usage conditions are within specified ranges. Renesas Electronics disclaims liability for malfunctions or accidents outside these ranges.

7. Semiconductor products have inherent failure rates. Unless designated for high reliability, Renesas Electronics products are not radiation-resistant. Users are responsible for implementing safety measures against bodily injury, fire, or public danger due to product failure or malfunction, including redundancy and fire control.

8. Contact Renesas Electronics sales for environmental compatibility details and ensure compliance with applicable laws and regulations (e.g., EU RoHS Directive). Renesas Electronics disclaims liability for non-compliance.

9. Renesas Electronics products and technologies shall not be used in products or systems prohibited by applicable laws or regulations. Users must comply with export control laws.

10. Buyers, distributors, or third parties selling or transferring Renesas Electronics products must notify the third party in advance of the document's contents and conditions.

11. This document shall not be reprinted or duplicated without prior written consent from Renesas Electronics.

12. Contact a Renesas Electronics sales office for any questions regarding this document or Renesas Electronics products.

(Note1) "Renesas Electronics" includes Renesas Electronics Corporation and its controlled subsidiaries.

(Note2) "Renesas Electronics product(s)" refers to any product developed or manufactured by or for Renesas Electronics.

Corporate Headquarters: TOYOSU FORESIA, 3-2-24 Toyosu, Koto-ku, Tokyo 135-0061, Japan www.renesas.com

Trademarks: Renesas and the Renesas logo are trademarks of Renesas Electronics Corporation. All other trademarks are the property of their respective owners.

Contact information: For further information, visit www.renesas.com/contact/.

PDF preview unavailable. Download the PDF instead.

REN r01an4721ej0100-motor APN 20190329 SetaPDF-Merger Component v2.27.0.1196 ©Setasign 2005-2020 (www.setasign.com)

Related Documents

Preview Renesas QE for Display [RX] Application Note: Guide to Embedded Display Development
This application note from Renesas provides a comprehensive guide to using QE for Display [RX], a plug-in for the e² studio IDE, for developing embedded systems with graphical displays on Renesas RX microcontrollers. Learn about GUI creation, display adjustment, and integration with emWin and AppWizard.
Preview Renesas RX Family EEPROM SPI Control Module: Firmware Integration Technology Guide
This application note from Renesas Electronics details the RX Family Clock Synchronous Control Module for EEPROM Access using Firmware Integration Technology (FIT). It covers API functions, hardware settings, software structure, and usage for R1EX25xxx and HN58X25xxx SPI serial EEPROMs with Renesas RX microcontrollers.
Preview Renesas RX Family SCI Module FIT Application Note
This application note from Renesas details the Serial Communications Interface (SCI) and Infrared Data Association (IrDA) modules for the RX Family of microcontrollers, utilizing Firmware Integration Technology (FIT). It covers API functions, configuration, target devices, and usage examples for embedded system development.
Preview Renesas Synergy CGC HAL Module Guide: Clock Configuration and Control
This guide details the Renesas Synergy Clock Generation Circuit (CGC) Hardware Abstraction Layer (HAL) module, covering its features, APIs, configuration, and usage in embedded applications. It explains how to manage system clocks, peripheral clocks, oscillators, and clock dividers for Renesas Synergy MCUs.
Preview Renesas RL78/G14, H8/36109 Migration Guide: H8 to RL78 ROM (Flash Memory)
A comprehensive guide from Renesas Electronics detailing the migration process from H8/36109 ROM to RL78/G14 Flash memory, covering functional differences, boot modes, user modes, and memory maps.
Preview Renesas Flash Programmer: Command Line Usage Guide
Learn how to automate microcontroller programming with the Renesas Flash Programmer (RFP) using command-line interfaces. This guide covers setup, project files, batch files, and rfp-cli examples for various Renesas MCU families.
Preview Renesas RL78/G23 Unique ID Read Driver Application Note
This Renesas application note details the RL78/G23 microcontroller's unique ID read driver, covering usage examples, software configuration, API functions, and a sample project for secure software IP and product management.
Preview Renesas EK-RA2L1 Example Project Bundle - Application Note
This application note describes the contents of the Renesas EK-RA2L1 Example Project Bundle, providing example code for Renesas Flexible Software Package (FSP) modules. It details supported kits, FSP versions, toolchains, and lists example projects with their toolchain compatibility.