STM32——舵机(机械臂、云台)控制指定角度(平滑运动控制、定时器PWM)

        使用STM32进行舵机控制,特别是在机械臂、云台等应用中,具有重要的意义。这些应用通常需要精准和平滑的运动控制,以实现复杂的任务或高精度的姿态调整。以下是舵机控制指定角度、平滑运动控制、以及定时器PWM在这些应用中的意义。

1. 舵机控制指定角度的意义

        舵机是广泛用于机械臂、云台和机器人系统中的执行器,能够将控制信号转换为精确的角度位置。控制舵机到指定角度对于这些系统的精度和可靠性至关重要:

  • 精准位置控制:在机械臂和云台中,指定角度控制能够确保设备的末端执行器或摄像头精确定位。例如,在机械臂抓取操作中,舵机需要精确地将手臂移动到目标位置,以避免失误。
  • 重复性和稳定性:通过设定指定角度,系统能够重复执行相同的动作,这对于自动化任务至关重要。机器人或云台的每次动作都必须高度一致,这样才能可靠地执行任务。

2. 平滑运动控制的意义

        平滑运动控制是指在角度变化时,舵机逐步调整,而不是瞬间跳转到目标角度。这种控制方式对于复杂系统的安全性和性能提升有显著作用:

  • 减少机械冲击:如果舵机角度突然变化,可能会导致机械结构受到冲击,影响设备的寿命和稳定性。平滑运动控制通过逐步调整角度,避免了这种冲击。
  • 提高控制精度:平滑的运动可以减少控制系统中的误差积累,尤其在多自由度机械臂中。每个关节的平滑运动有助于整体系统更加精确地完成任务。
  • 改善用户体验:对于云台控制,平滑的运动会使得摄像头的转动更加自然,减少抖动和不连贯的运动,从而提高视频的拍摄效果。

用于将舵机角度从当前角度逐步调整到目标角度,以实现平滑的角度变化。其实现步骤如下:

  • 定义了当前的角度变量(currentAngle1~6),初始值设定为舵机的默认中位值(通常为90度或其他默认角度)。
  • 使用 while 循环,每次调整舵机角度,并通过比较当前角度和目标角度的差异,决定每个舵机是否需要增加或减少角度。
  • 如果目标角度与当前角度的差异大于步进值(step),则调整当前角度。否则,直接将当前角度设为目标角度。
  • 通过 PWM_SetCompareX() 设置各舵机的PWM信号。
  • 通过 Delay_us(delay) 实现每次调整后的延迟,以控制舵机运动的速度。

3. 实际应用场景

机械臂控制:
  • 任务执行:在自动化生产线或仓库机器人中,机械臂需要精确、平滑地移动到指定位置以抓取或放置物品。舵机的精确控制确保了任务的成功率。
  • 多关节协调:平滑的运动和同步的舵机控制,能够让机械臂的多个关节协调动作,避免因突然变化造成的机械震动或误差。
云台控制:
  • 摄像头追踪:在监控系统或无人机应用中,云台需要准确地将摄像头对准目标。舵机的精准角度控制和平滑移动可以避免画面抖动,确保视频质量。
  • 自动跟踪:在目标跟踪应用中,云台需要实时、平滑地调整角度,以持续跟踪移动目标。

以下是控制舵机输出角度的代码: 

#include "stm32f10x.h"                  // STM32F10x设备的头文件,包含了与芯片相关的寄存器定义
#include "PWM.h"                        // 用于控制PWM信号的头文件
#include <math.h>                       // 数学函数库,比如fabs函数,用于计算浮点数的绝对值
#include "Delay.h"                      // 延迟函数头文件,提供精确的延迟功能

void Servo_Init(void)                   // 舵机初始化函数
{
    PWM_Init();                         // 初始化PWM,用于控制舵机
}

void Servo_SetAngle(float Angle1, float Angle2) // 设置两个舵机角度的函数
{
    PWM_SetCompare1(Angle1 / 180 * 2000 + 500); // 将Angle1转换为对应的PWM脉宽,设置到PWM通道1
    PWM_SetCompare2(Angle2 / 180 * 2000 + 500); // 将Angle2转换为对应的PWM脉宽,设置到PWM通道2
}

void Servo_SetAllAngle(float Angle1, float Angle2, float Angle3, float Angle4, float Angle5, float Angle6) // 设置六个舵机角度的函数
{
    PWM_SetCompare1((Angle1 + 22) / 180 * 2000 + 500); // 将Angle1(加22度偏移)转换为对应的PWM脉宽,设置到PWM通道1
    PWM_SetCompare2(Angle2 / 180 * 2000 + 500);        // 将Angle2转换为对应的PWM脉宽,设置到PWM通道2
    PWM_SetCompare3(Angle3 / 180 * 2000 + 500);        // 将Angle3转换为对应的PWM脉宽,设置到PWM通道3
    PWM_SetCompare4(Angle4 / 180 * 2000 + 500);        // 将Angle4转换为对应的PWM脉宽,设置到PWM通道4
    PWM_SetCompare5(Angle5 / 180 * 2000 + 500);        // 将Angle5转换为对应的PWM脉宽,设置到PWM通道5
    PWM_SetCompare6(Angle6 / 180 * 2000 + 500);        // 将Angle6转换为对应的PWM脉宽,设置到PWM通道6
}

void Servo_SetAngleGradually(float targetAngle1, float targetAngle2, float targetAngle3, float targetAngle4, float targetAngle5, float targetAngle6, float step, unsigned int delay) // 逐步调整六个舵机角度的函数
{
    static float currentAngle1 = 90; // 定义当前角度1的静态变量,初始值为90度
    static float currentAngle2 = 90; // 定义当前角度2的静态变量,初始值为90度
    static float currentAngle3 = 90; // 定义当前角度3的静态变量,初始值为90度
    static float currentAngle4 = 90; // 定义当前角度4的静态变量,初始值为90度
    static float currentAngle5 = 90; // 定义当前角度5的静态变量,初始值为90度
    static float currentAngle6 = 60; // 定义当前角度6的静态变量,初始值为60度

    while (fabs(targetAngle1 - currentAngle1) > step ||  // 如果目标角度和当前角度的差值超过步进值,继续调整角度1
           fabs(targetAngle2 - currentAngle2) > step ||  // 如果目标角度和当前角度的差值超过步进值,继续调整角度2
           fabs(targetAngle3 - currentAngle3) > step ||  // 如果目标角度和当前角度的差值超过步进值,继续调整角度3
           fabs(targetAngle4 - currentAngle4) > step ||  // 如果目标角度和当前角度的差值超过步进值,继续调整角度4
           fabs(targetAngle5 - currentAngle5) > step ||  // 如果目标角度和当前角度的差值超过步进值,继续调整角度5
           fabs(targetAngle6 - currentAngle6) > step)    // 如果目标角度和当前角度的差值超过步进值,继续调整角度6
    {
        if (fabs(targetAngle1 - currentAngle1) > step)  // 如果目标角度和当前角度的差值超过步进值
            currentAngle1 += (targetAngle1 > currentAngle1) ? step : -step; // 调整角度1,增加或减少步进值
        else
            currentAngle1 = targetAngle1;  // 如果差值不超过步进值,直接将角度1设置为目标角度

        if (fabs(targetAngle2 - currentAngle2) > step)  // 如果目标角度和当前角度的差值超过步进值
            currentAngle2 += (targetAngle2 > currentAngle2) ? step : -step; // 调整角度2,增加或减少步进值
        else
            currentAngle2 = targetAngle2;  // 如果差值不超过步进值,直接将角度2设置为目标角度

        if (fabs(targetAngle3 - currentAngle3) > step)  // 如果目标角度和当前角度的差值超过步进值
            currentAngle3 += (targetAngle3 > currentAngle3) ? step : -step; // 调整角度3,增加或减少步进值
        else
            currentAngle3 = targetAngle3;  // 如果差值不超过步进值,直接将角度3设置为目标角度

        if (fabs(targetAngle4 - currentAngle4) > step)  // 如果目标角度和当前角度的差值超过步进值
            currentAngle4 += (targetAngle4 > currentAngle4) ? step : -step; // 调整角度4,增加或减少步进值
        else
            currentAngle4 = targetAngle4;  // 如果差值不超过步进值,直接将角度4设置为目标角度

        if (fabs(targetAngle5 - currentAngle5) > step)  // 如果目标角度和当前角度的差值超过步进值
            currentAngle5 += (targetAngle5 > currentAngle5) ? step : -step; // 调整角度5,增加或减少步进值
        else
            currentAngle5 = targetAngle5;  // 如果差值不超过步进值,直接将角度5设置为目标角度

        if (fabs(targetAngle6 - currentAngle6) > step)  // 如果目标角度和当前角度的差值超过步进值
            currentAngle6 += (targetAngle6 > currentAngle6) ? step : -step; // 调整角度6,增加或减少步进值
        else
            currentAngle6 = targetAngle6;  // 如果差值不超过步进值,直接将角度6设置为目标角度

        PWM_SetCompare1(currentAngle1 / 180 * 2000 + 500); // 将当前角度1转换为PWM脉宽,设置到PWM通道1
        PWM_SetCompare2(currentAngle2 / 180 * 2000 + 500); // 将当前角度2转换为PWM脉宽,设置到PWM通道2
        PWM_SetCompare3(currentAngle3 / 180 * 2000 + 500); // 将当前角度3转换为PWM脉宽,设置到PWM通道3
        PWM_SetCompare4(currentAngle4 / 180 * 2000 + 500); // 将当前角度4转换为PWM脉宽,设置到PWM通道4
        PWM_SetCompare5(currentAngle5 / 180 * 2000 + 500); // 将当前角度5转换为PWM脉宽,设置到PWM通道5
        PWM_SetCompare6(currentAngle6 / 180 * 2000 + 500); // 将当前角度6转换为PWM脉宽,设置到PWM通道6

        Delay_us(delay); // 延迟,单位为微秒,用于控制舵机运动速度
    }
}
#ifndef __SERVO_H
#define __SERVO_H
void Servo_SetAngle(float Angle1,float Angle2);
void Servo_Init(void);
void Servo_SetAllAngle(float Angle1,float Angle2,float Angle3,float Angle4,float Angle5,float Angle6);
void Servo_SetAngleGradually(float targetAngle1, float targetAngle2, float targetAngle3, float targetAngle4, float targetAngle5, float targetAngle6, float step, unsigned int delay);
#endif

 以下是多个定时器多个通道分别输出PWM的代码:

#include "stm32f10x.h"                  // Device header

void PWM_Init(void)
{
	RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
	RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);

	GPIO_InitTypeDef GPIO_InitStructure;
	GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
	GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_0;
	GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
	GPIO_Init(GPIOA, &GPIO_InitStructure);

	TIM_InternalClockConfig(TIM2);

	TIM_TimeBaseInitTypeDef TIM_TimerBaseInitStructure;
	TIM_TimerBaseInitStructure.TIM_ClockDivision = TIM_CKD_DIV1;
	TIM_TimerBaseInitStructure.TIM_CounterMode = TIM_CKD_DIV1;
	TIM_TimerBaseInitStructure.TIM_Period = 20000 - 1;//ARR
	TIM_TimerBaseInitStructure.TIM_Prescaler = 72 - 1;//PSC
	TIM_TimerBaseInitStructure.TIM_RepetitionCounter = 0;
	TIM_TimeBaseInit(TIM2, &TIM_TimerBaseInitStructure);

	TIM_OCInitTypeDef TIM_OCInitStructure;
	TIM_OCStructInit(&TIM_OCInitStructure);
	TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
	TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
	TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
	TIM_OCInitStructure.TIM_Pulse = 0;//CCR
	TIM_OC1Init(TIM2, &TIM_OCInitStructure);
	TIM_OC2Init(TIM2, &TIM_OCInitStructure);

	TIM_Cmd(TIM2, ENABLE);
	
	RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
	RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
	RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);

	GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
	GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
	GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
	GPIO_Init(GPIOA, &GPIO_InitStructure);

	
	GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
	GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
	GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
	GPIO_Init(GPIOB, &GPIO_InitStructure);
	
	TIM_InternalClockConfig(TIM3);

	TIM_TimerBaseInitStructure.TIM_ClockDivision = TIM_CKD_DIV1;
	TIM_TimerBaseInitStructure.TIM_CounterMode = TIM_CKD_DIV1;
	TIM_TimerBaseInitStructure.TIM_Period = 20000 - 1;//ARR
	TIM_TimerBaseInitStructure.TIM_Prescaler = 72 - 1;//PSC
	TIM_TimerBaseInitStructure.TIM_RepetitionCounter = 0;
	TIM_TimeBaseInit(TIM3, &TIM_TimerBaseInitStructure);

	TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
	TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
	TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
	TIM_OCInitStructure.TIM_Pulse = 0;//CCR
	TIM_OC1Init(TIM3, &TIM_OCInitStructure);
	TIM_OC2Init(TIM3, &TIM_OCInitStructure);
	TIM_OC3Init(TIM3, &TIM_OCInitStructure);
	TIM_OC4Init(TIM3, &TIM_OCInitStructure);
	
	TIM_Cmd(TIM3, ENABLE);
}

void PWM_SetCompare1(unsigned int Compare)
{
	TIM_SetCompare1(TIM2, Compare);
}
void PWM_SetCompare2(unsigned int Compare)
{
	TIM_SetCompare2(TIM2, Compare);
}

void PWM_SetCompare3(unsigned int Compare)
{
	TIM_SetCompare1(TIM3, Compare);
}
void PWM_SetCompare4(unsigned int Compare)
{
	TIM_SetCompare2(TIM3, Compare);
}

void PWM_SetCompare5(unsigned int Compare)
{
	TIM_SetCompare3(TIM3, Compare);
}
void PWM_SetCompare6(unsigned int Compare)
{
	TIM_SetCompare4(TIM3, Compare);
}
#ifndef  __PWM_H
#define  __PWM_H

void PWM_SetCompare1(unsigned int Compare);
void PWM_SetCompare2(unsigned int Compare);

void PWM_SetCompare3(unsigned int Compare);
void PWM_SetCompare4(unsigned int Compare);

void PWM_SetCompare5(unsigned int Compare);
void PWM_SetCompare6(unsigned int Compare);

void PWM_Init(void);
#endif

总结

这个代码用于控制多个舵机的角度调整,其中包含舵机的初始化、设置单个/多个舵机角度,以及逐渐调整多个舵机角度的功能。 Servo_SetAngleGradually 函数通过步进方式实现平滑的角度变化,适用于需要平滑控制多个舵机的场合,比如机械臂、机器人等应用。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值