Robofun 機器人論壇

 找回密碼
 申請會員
搜索
熱搜: 活動 交友 discuz
查看: 8840|回復: 21
打印 上一主題 下一主題

要如何讓馬達動呢?

[複製鏈接]
1#
發表於 2010-5-18 13:41:31 | 顯示全部樓層
本帖最後由 acen2008 於 2010-5-18 14:21 編輯

HI~
rcservo_SendPWMPulses和rcservo_SetServo是設定單一channel的函數
所以channel參數只能輸入0、1、2、3...、23喔 (要使用到23以上要小改一下RoBoard)
而rcservo_Initialize()中的channel是可設定為複數的,假如你要使用channel 0、1、4
輸出PWM,則channel = RCSERVO_USECHANNEL0 + RCSERVO_USECHANNEL1 +
RCSERVO_USECHANNEL4,假如只要用到channel 1的話,
channel = RCSERVO_USECHANNEL1 就可以了。

下面的code是我測過可動的,不妨參考一下:)

#include <stdio.h>
#include <conio.h>
#include <roboard.h>

int main(void)
{
        //使用的Library是V1.6版要呼叫roboio_SetRBVer(),不是則不用
        //使用的硬體是RB100,輸入參數=RB_100,使用RB110,輸入參數=RB_110
        //Note : RB110只有16組PWM
        roboio_SetRBVer(RB_100);
       
        //rcservo_SetServo是設定單一channel的函數,channel = 0 ~ 23
        //必須在rcservo_Initialize之前呼叫
        rcservo_SetServo(0, RCSERVO_SERVO_DEFAULT_NOFB);
        rcservo_SetServo(1, RCSERVO_SERVO_DEFAULT_NOFB);

        //初始化:把Channel 0和1切換成PWM輸出,其他channel為GPIO
        if(rcservo_Initialize(RCSERVO_USECHANNEL0 +
                                       RCSERVO_USECHANNEL1) == false)
        {
                //初始化失敗則印出錯誤訊息
                printf("%s",roboio_GetErrMsg());
                rcservo_Close();
                return -1;
        }

        //進入PWM Mode
        rcservo_EnterPWMMode();
       
        //將period = 10000us,duty = 1500us,count = 50 次的PWM從channel 0 輸出
        //將period = 10000us,duty = 1700us,count = 10 次的PWM從channel 1 輸出
        //rcservo_SendPWMPulses是設定單一channel的函數,channel = 0 ~ 23
        rcservo_SendPWMPulses(0,10000L,1500L,50L);
        rcservo_SendPWMPulses(1,10000L,1700L,10L);

        printf("Send PWM pulse.\n");

        //等channel 0 的PWM送完
        while (rcservo_IsPWMCompleted(0) == false);

        //結束程式
        rcservo_Close();
        return 0;
}
2#
發表於 2010-5-19 10:03:12 | 顯示全部樓層
HI~
圖中你的馬達接到channel 2了(S3)
請換到channel 0和1應該就可以了
另一種方法,你將程式中的channel改為channel 2也可以:)
您需要登錄後才可以回帖 登錄 | 申請會員

本版積分規則

小黑屋|手機版|Archiver|機器人論壇 from 2005.07

GMT+8, 2024-5-11 03:36 , Processed in 0.144151 second(s), 7 queries , Apc On.

Powered by Discuz! X3.2

© 2001-2013 Comsenz Inc.

快速回復 返回頂部 返回列表