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

Dependencies:   mbed CalPID motorout ros_lib_melodic MotorController_AbsEC

Committer:
ayu13
Date:
Tue Jul 20 06:41:29 2021 +0000
Revision:
8:9656790eea17
Parent:
7:038ea29c5a97
Child:
9:95f6b9f54395
ROS_OK

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