DRのPS3での操作用(アームの開閉をコントローラで制御可能)

Dependencies:   mbed CalPID motorout ros_lib_melodic MotorController_AbsEC

Committer:
koheim
Date:
Sun Jul 25 13:57:43 2021 +0000
Revision:
11:df2acf22123e
Parent:
10:c1ca3db7177c
Child:
12:c2bb0a9587b5
a; ;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
ayu13 0:83b2c6a67cce 1 ////c = center arm
ayu13 0:83b2c6a67cce 2 #include "mbed.h"
ayu13 0:83b2c6a67cce 3 #include "AMT21.h"
ayu13 0:83b2c6a67cce 4 #include "CalPID.h"
ayu13 0:83b2c6a67cce 5 #include "KondoServo.h"
ayu13 0:83b2c6a67cce 6 #include "MotorController.h"
ayu13 0:83b2c6a67cce 7 #include <stdlib.h>
ayu13 0:83b2c6a67cce 8 #include <ros.h>
ayu13 0:83b2c6a67cce 9 #include <std_msgs/String.h>
ayu13 0:83b2c6a67cce 10 #include <geometry_msgs/Point.h>
ayu13 0:83b2c6a67cce 11
ayu13 0:83b2c6a67cce 12 ///////////////// 宣言部分 //////////////////////
ayu13 0:83b2c6a67cce 13 #ifndef M_PI
ayu13 0:83b2c6a67cce 14 #define M_PI 3.14159265359f
ayu13 0:83b2c6a67cce 15 #endif
ayu13 1:c0a3e4589a8f 16 #define DELTA_T 0.01 //制御周期
ayu13 1:c0a3e4589a8f 17 #define DUTY_MAX 0.07 //duty比の最大値
ayu13 6:e6b303ea6439 18 #define OMEGA_MAX 0.25 //速度制御を利用した角度制御での角速度の最大値
ayu13 0:83b2c6a67cce 19 #define NUM_DATA 270
ayu13 0:83b2c6a67cce 20
koheim 11:df2acf22123e 21 int state = 1;
ayu13 5:4fba3e91741f 22
ayu13 0:83b2c6a67cce 23 ////角度制御(アブソリュートエンコーダ)/////
ayu13 0:83b2c6a67cce 24 Timer timer;
ayu13 0:83b2c6a67cce 25 CalPID speed_pid(0.08,0,0.0008,DELTA_T,DUTY_MAX); //速度制御のPD計算
ayu13 3:78b608ba0286 26 CalPID angle_duty_pid(0,0,0,DELTA_T,DUTY_MAX); //角度制御(duty式)のPD計算
ayu13 6:e6b303ea6439 27 CalPID angle_omega_pid(5.0,0,0.0032,DELTA_T,OMEGA_MAX);//角度制御(速度式)のPD計算
ayu13 0:83b2c6a67cce 28 Amt21 amt(p9,p10,p8); //Amt21 (PinName tx,PinName rx,PinName mode):serial_(tx,rx),rs485_mode(mode)
ayu13 0:83b2c6a67cce 29 MotorController motor(p26,p25,DELTA_T,amt,speed_pid,angle_duty_pid,angle_omega_pid); //MotorController(PinName motor_p_, PinName motor_n_,double dt, Amt21 &ec, CalPID &sc_, CalPID &ac_duty, CalPID &ac_omega)
ayu13 5:4fba3e91741f 30 double degToRad(double x);
ayu13 0:83b2c6a67cce 31 double target_rad=0;
ayu13 0:83b2c6a67cce 32 double target_deg = 0;
ayu13 7:038ea29c5a97 33 double turn_deg = 0;
ayu13 7:038ea29c5a97 34 double turn_rad = 0;
ayu13 9:95f6b9f54395 35 DigitalIn toggle1(p16, PullUp); //トグルright(マイコン側)
ayu13 9:95f6b9f54395 36 DigitalIn toggle2(p20, PullUp); //トグルleft(外側)
ayu13 0:83b2c6a67cce 37
ayu13 0:83b2c6a67cce 38 ////先端アーム(サーボ)/////
ayu13 0:83b2c6a67cce 39 DigitalIn ts_c1(p6, PullUp);
ayu13 0:83b2c6a67cce 40 DigitalIn ts_c2(p7, PullUp);
ayu13 0:83b2c6a67cce 41 KondoServo servo_c(p13, p14);
ayu13 0:83b2c6a67cce 42 double servoDeg(double servo_value);
ayu13 10:c1ca3db7177c 43 void touchGrab(); //タッチセンサ反応したらサーボ掴む
koheim 11:df2acf22123e 44 float deg_c_grab = 11000;
ayu13 6:e6b303ea6439 45 float deg_c_open = 8300;
ayu13 0:83b2c6a67cce 46
ayu13 9:95f6b9f54395 47 ////データ記録関連/////
ayu13 4:3abefa13c2e3 48 double now_deg=0;
ayu13 0:83b2c6a67cce 49 double now_count=0;
ayu13 0:83b2c6a67cce 50
ayu13 2:b728a6564520 51 ///////////////// ROS /////////////////
ayu13 9:95f6b9f54395 52 DigitalOut myled1(LED1);
ayu13 2:b728a6564520 53 DigitalOut myled2(LED2);
ayu13 2:b728a6564520 54 DigitalOut myled3(LED3);
ayu13 2:b728a6564520 55 DigitalOut myled4(LED4);
ayu13 7:038ea29c5a97 56 float arm_turn=0,arm_deg=0,arm_rad=0;
ayu13 2:b728a6564520 57 void cArmCallback(const geometry_msgs::Point &arm_state)
ayu13 2:b728a6564520 58 {
ayu13 10:c1ca3db7177c 59 arm_turn = arm_state.x; //左回転=1、右回転=2
ayu13 10:c1ca3db7177c 60 arm_deg = arm_state.y; //目標角度
ayu13 2:b728a6564520 61 }
ayu13 2:b728a6564520 62 ros::NodeHandle nh;
ayu13 2:b728a6564520 63 ros::Subscriber<geometry_msgs::Point> sub("/arm",&cArmCallback);
ayu13 2:b728a6564520 64
ayu13 0:83b2c6a67cce 65 int main()
ayu13 0:83b2c6a67cce 66 {
koheim 11:df2acf22123e 67 int mode = 0;
ayu13 5:4fba3e91741f 68 myled1 = 0; //目標角度以上離れている:点灯
ayu13 5:4fba3e91741f 69 myled2 = 0; //通信で欲しい値が送られているとき:点灯
ayu13 8:9656790eea17 70 myled3 = 0; //state2に入ったとき←基本不要
ayu13 5:4fba3e91741f 71 myled4 = 0; //サーボを掴む→点灯.離す→消灯
ayu13 5:4fba3e91741f 72
ayu13 0:83b2c6a67cce 73 ///////// ROS /////////
koheim 11:df2acf22123e 74 nh.getHardware()->setBaud(115200);
ayu13 0:83b2c6a67cce 75 nh.initNode();
ayu13 0:83b2c6a67cce 76 nh.subscribe(sub);
ayu13 0:83b2c6a67cce 77
ayu13 0:83b2c6a67cce 78 timer.reset();
ayu13 0:83b2c6a67cce 79 timer.start();
ayu13 0:83b2c6a67cce 80
ayu13 0:83b2c6a67cce 81 motor.setEquation(0.0523,0.0148,0.0459,-0.0341); //Excel"omega_controll"の図より
koheim 11:df2acf22123e 82 ////////////////////////////////////////
koheim 11:df2acf22123e 83 /*arm_turn = 2; //左回転=1、右回転=2
koheim 11:df2acf22123e 84 arm_deg = -90; //目標角度*/
koheim 11:df2acf22123e 85 ///////////////////////////////////////
ayu13 0:83b2c6a67cce 86
ayu13 0:83b2c6a67cce 87 while (1) {
ayu13 8:9656790eea17 88 nh.spinOnce(); //ROS
ayu13 4:3abefa13c2e3 89
ayu13 5:4fba3e91741f 90 if(timer.read()>DELTA_T) {
ayu13 8:9656790eea17 91 if(arm_turn==2&&arm_deg==-10) { //動作確認(通信)用
ayu13 5:4fba3e91741f 92 myled2 = 1;
ayu13 0:83b2c6a67cce 93 }
ayu13 5:4fba3e91741f 94 arm_rad = degToRad(arm_deg);
ayu13 7:038ea29c5a97 95 target_deg = arm_deg;
ayu13 7:038ea29c5a97 96 target_rad = arm_rad;
ayu13 0:83b2c6a67cce 97
ayu13 10:c1ca3db7177c 98 if(state == 0) { //トグルスイッチONでstate=1へ.
ayu13 8:9656790eea17 99 ///トグルスイッチ1////マイコン方向
ayu13 10:c1ca3db7177c 100 if(toggle1 == 0) { //トグルスイッチ1(mbed側)ONで初start
ayu13 6:e6b303ea6439 101 wait_us(50);
ayu13 6:e6b303ea6439 102 if(toggle1 == 0) {
ayu13 10:c1ca3db7177c 103 state++;
ayu13 6:e6b303ea6439 104 }
ayu13 6:e6b303ea6439 105 }
ayu13 6:e6b303ea6439 106 }
ayu13 10:c1ca3db7177c 107 if(state == 1) { //回転方向の変数"arm_turn"に1か2が代入されたらstate=2へ.
ayu13 7:038ea29c5a97 108 if(arm_turn == 1) {
ayu13 7:038ea29c5a97 109 turn_deg = 90;
ayu13 10:c1ca3db7177c 110 state++;
ayu13 7:038ea29c5a97 111 } else if(arm_turn == 2) {
ayu13 7:038ea29c5a97 112 turn_deg = -90;
ayu13 10:c1ca3db7177c 113 state++;
ayu13 7:038ea29c5a97 114 }
ayu13 7:038ea29c5a97 115 turn_rad = degToRad(turn_deg);
ayu13 10:c1ca3db7177c 116 } else if(state == 2) { //サーボを離してそのまますぐstate=3へ.
ayu13 10:c1ca3db7177c 117 servo_c.set_degree(0,servoDeg(deg_c_open)); //servo_c離す
ayu13 5:4fba3e91741f 118 state++;
ayu13 10:c1ca3db7177c 119 } else if (state == 3) {//タッチセンサがハンドルに反応したらサーボで掴んでstate=4へ.
ayu13 5:4fba3e91741f 120 myled3 = 1;
ayu13 10:c1ca3db7177c 121 if(fabs(now_deg-turn_deg) > 0.5) { //現在角度と目標角度が0.5°以上離れている間回す
ayu13 10:c1ca3db7177c 122 myled1 = 1; //LED1 点灯
ayu13 10:c1ca3db7177c 123 motor.AcOmega(turn_rad); //速度式角度制御
ayu13 5:4fba3e91741f 124 } else { //目標角度に達したら停止
ayu13 5:4fba3e91741f 125 myled1=0; //LED1 消灯
ayu13 5:4fba3e91741f 126 motor.stop();
ayu13 5:4fba3e91741f 127 }
ayu13 10:c1ca3db7177c 128 touchGrab();
ayu13 10:c1ca3db7177c 129 } else if (state == 4) {//目標角度を設定してそのまますぐstate=5へ.
ayu13 5:4fba3e91741f 130 myled3 = 0;
koheim 11:df2acf22123e 131 if(mode == 0){
koheim 11:df2acf22123e 132 target_rad = arm_rad;
koheim 11:df2acf22123e 133 target_deg = arm_deg;
koheim 11:df2acf22123e 134 }
koheim 11:df2acf22123e 135 else if(mode == 1){
koheim 11:df2acf22123e 136 target_deg = 45;
koheim 11:df2acf22123e 137 target_rad = degToRad(target_deg);
koheim 11:df2acf22123e 138 }
koheim 11:df2acf22123e 139 else if(mode == 2){
koheim 11:df2acf22123e 140 target_deg = -45;
koheim 11:df2acf22123e 141 target_rad = degToRad(target_deg);
koheim 11:df2acf22123e 142 }
ayu13 5:4fba3e91741f 143 state++;
ayu13 10:c1ca3db7177c 144 } else if (state == 5) {//目標角度に近づいたら停止してサーボを離す.
ayu13 10:c1ca3db7177c 145 if(fabs(now_deg-target_deg) > 0.5) { //現在角度と目標角度が0.5°以上離れている間回す
ayu13 10:c1ca3db7177c 146 myled1 = 1; //LED1 点灯
ayu13 10:c1ca3db7177c 147 motor.AcOmega(target_rad); //速度式角度制御
ayu13 5:4fba3e91741f 148 } else { //目標角度に達したら停止
ayu13 10:c1ca3db7177c 149 myled1 = 0; //LED1 消灯
ayu13 5:4fba3e91741f 150 motor.stop();
koheim 11:df2acf22123e 151 //servo_c.set_degree(0,servoDeg(deg_c_open)); //servo_c離す
ayu13 5:4fba3e91741f 152 myled4 = 0;
koheim 11:df2acf22123e 153 if(mode == 0){
koheim 11:df2acf22123e 154 mode = 1;
koheim 11:df2acf22123e 155 }
koheim 11:df2acf22123e 156 else{
koheim 11:df2acf22123e 157 mode = 3-mode;
koheim 11:df2acf22123e 158 }
koheim 11:df2acf22123e 159 state = 4; /////////////////////連続して動かす時はここのコメントアウト外す.
ayu13 3:78b608ba0286 160 }
ayu13 0:83b2c6a67cce 161 }
ayu13 5:4fba3e91741f 162
ayu13 0:83b2c6a67cce 163 amt.rewriteCount();
ayu13 0:83b2c6a67cce 164 amt.calOmega();
ayu13 4:3abefa13c2e3 165 now_deg = amt.getDeg();
ayu13 0:83b2c6a67cce 166 now_count=amt.getCount();
ayu13 0:83b2c6a67cce 167
ayu13 0:83b2c6a67cce 168 timer.reset();
ayu13 0:83b2c6a67cce 169 }
ayu13 0:83b2c6a67cce 170 wait_us(10);
ayu13 0:83b2c6a67cce 171 }
ayu13 0:83b2c6a67cce 172 }
ayu13 0:83b2c6a67cce 173
ayu13 0:83b2c6a67cce 174 ///////////////// 関数宣言部分 //////////////////////
ayu13 0:83b2c6a67cce 175 double servoDeg(double servo_value)
ayu13 0:83b2c6a67cce 176 {
ayu13 0:83b2c6a67cce 177 return (servo_value - 3500)*270/(11500 - 3500);
ayu13 0:83b2c6a67cce 178 }
ayu13 2:b728a6564520 179 double degToRad(double x)
ayu13 2:b728a6564520 180 {
ayu13 2:b728a6564520 181 return x*M_PI/180;
ayu13 5:4fba3e91741f 182 }
ayu13 5:4fba3e91741f 183 void touchGrab()
ayu13 5:4fba3e91741f 184 {
ayu13 5:4fba3e91741f 185 if(ts_c1 == 0) { //タッチセンサ反応したらハンドルを掴む
ayu13 5:4fba3e91741f 186 wait_us(50);
ayu13 5:4fba3e91741f 187 if(ts_c1 == 0) {
ayu13 5:4fba3e91741f 188 servo_c.set_degree(0,servoDeg(deg_c_grab)); //servo_c掴む
ayu13 5:4fba3e91741f 189 state++;
ayu13 5:4fba3e91741f 190 myled4=1; //LED4 点灯
ayu13 5:4fba3e91741f 191 }
ayu13 5:4fba3e91741f 192 }
ayu13 0:83b2c6a67cce 193 }