DRのPS3での操作用

Dependencies:   mbed CalPID motorout ros_lib_melodic MotorController_AbsEC

Committer:
ayu13
Date:
Tue Jul 20 08:57:36 2021 +0000
Revision:
9:95f6b9f54395
Parent:
8:9656790eea17
Child:
10:c1ca3db7177c
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 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 9:95f6b9f54395 43 void touchGrab(); //タッチセンサ
ayu13 6:e6b303ea6439 44 float deg_c_grab = 10600;
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 8:9656790eea17 59 arm_turn = arm_state.x; //左回転=1、右回転=2
ayu13 2:b728a6564520 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 {
ayu13 5:4fba3e91741f 67 myled1 = 0; //目標角度以上離れている:点灯
ayu13 5:4fba3e91741f 68 myled2 = 0; //通信で欲しい値が送られているとき:点灯
ayu13 8:9656790eea17 69 myled3 = 0; //state2に入ったとき←基本不要
ayu13 5:4fba3e91741f 70 myled4 = 0; //サーボを掴む→点灯.離す→消灯
ayu13 5:4fba3e91741f 71
ayu13 0:83b2c6a67cce 72 ///////// ROS /////////
ayu13 1:c0a3e4589a8f 73 nh.getHardware()->setBaud(921600);
ayu13 0:83b2c6a67cce 74 nh.initNode();
ayu13 0:83b2c6a67cce 75 nh.subscribe(sub);
ayu13 0:83b2c6a67cce 76
ayu13 0:83b2c6a67cce 77 timer.reset();
ayu13 0:83b2c6a67cce 78 timer.start();
ayu13 0:83b2c6a67cce 79
ayu13 0:83b2c6a67cce 80 motor.setEquation(0.0523,0.0148,0.0459,-0.0341); //Excel"omega_controll"の図より
ayu13 0:83b2c6a67cce 81
ayu13 0:83b2c6a67cce 82 while (1) {
ayu13 8:9656790eea17 83 nh.spinOnce(); //ROS
ayu13 4:3abefa13c2e3 84
ayu13 5:4fba3e91741f 85 if(timer.read()>DELTA_T) {
ayu13 8:9656790eea17 86 if(arm_turn==2&&arm_deg==-10) { //動作確認(通信)用
ayu13 5:4fba3e91741f 87 myled2 = 1;
ayu13 0:83b2c6a67cce 88 }
ayu13 5:4fba3e91741f 89 arm_rad = degToRad(arm_deg);
ayu13 7:038ea29c5a97 90 target_deg = arm_deg;
ayu13 7:038ea29c5a97 91 target_rad = arm_rad;
ayu13 0:83b2c6a67cce 92
ayu13 5:4fba3e91741f 93 if(state == 0) {
ayu13 8:9656790eea17 94 ///トグルスイッチ1////マイコン方向
ayu13 6:e6b303ea6439 95 if(toggle1 == 0) { //トグルスイッチ1(mbed側)ONで初start
ayu13 6:e6b303ea6439 96 wait_us(50);
ayu13 6:e6b303ea6439 97 if(toggle1 == 0) {
ayu13 6:e6b303ea6439 98 state ++;
ayu13 6:e6b303ea6439 99 }
ayu13 6:e6b303ea6439 100 }
ayu13 6:e6b303ea6439 101 }
ayu13 6:e6b303ea6439 102 if(state == 1) {
ayu13 7:038ea29c5a97 103 if(arm_turn == 1) {
ayu13 7:038ea29c5a97 104 turn_deg = 90;
ayu13 7:038ea29c5a97 105 } else if(arm_turn == 2) {
ayu13 7:038ea29c5a97 106 turn_deg = -90;
ayu13 7:038ea29c5a97 107 }
ayu13 7:038ea29c5a97 108 turn_rad = degToRad(turn_deg);
ayu13 6:e6b303ea6439 109 servo_c.set_degree(0,servoDeg(deg_c_open)); //servo_c離す
ayu13 5:4fba3e91741f 110 state++;
ayu13 6:e6b303ea6439 111 } else if (state == 2) {
ayu13 5:4fba3e91741f 112 myled3 = 1;
ayu13 7:038ea29c5a97 113 if(fabs(now_deg-turn_deg) > 0.5) { //現在角度と目標角度が0.5°以上離れている間回す
ayu13 5:4fba3e91741f 114 myled1 = 1; //LED1 点灯
ayu13 7:038ea29c5a97 115 motor.AcOmega(turn_rad); //速度式角度制御
ayu13 5:4fba3e91741f 116 } else { //目標角度に達したら停止
ayu13 5:4fba3e91741f 117 myled1=0; //LED1 消灯
ayu13 5:4fba3e91741f 118 motor.stop();
ayu13 5:4fba3e91741f 119 }
ayu13 5:4fba3e91741f 120 touchGrab(); //タッチセンサ
ayu13 6:e6b303ea6439 121 } else if (state == 3) {
ayu13 5:4fba3e91741f 122 myled3 = 0;
ayu13 5:4fba3e91741f 123 target_rad = arm_rad;
ayu13 5:4fba3e91741f 124 target_deg = arm_deg;
ayu13 5:4fba3e91741f 125 state++;
ayu13 6:e6b303ea6439 126 } else if (state == 4) {
ayu13 5:4fba3e91741f 127 if(fabs(now_deg-target_deg) > 0.5) { //現在角度と目標角度が0.5°以上離れている間回す
ayu13 5:4fba3e91741f 128 myled1 = 1; //LED1 点灯
ayu13 3:78b608ba0286 129 motor.AcOmega(target_rad); //速度式角度制御
ayu13 5:4fba3e91741f 130 } else { //目標角度に達したら停止
ayu13 5:4fba3e91741f 131 myled1=0; //LED1 消灯
ayu13 5:4fba3e91741f 132 motor.stop();
ayu13 5:4fba3e91741f 133 servo_c.set_degree(0,servoDeg(deg_c_open)); //servo_c離す
ayu13 5:4fba3e91741f 134 myled4 = 0;
ayu13 6:e6b303ea6439 135 // state = 0;
ayu13 3:78b608ba0286 136 }
ayu13 0:83b2c6a67cce 137 }
ayu13 5:4fba3e91741f 138
ayu13 0:83b2c6a67cce 139 amt.rewriteCount();
ayu13 0:83b2c6a67cce 140 amt.calOmega();
ayu13 4:3abefa13c2e3 141 now_deg = amt.getDeg();
ayu13 0:83b2c6a67cce 142 now_count=amt.getCount();
ayu13 0:83b2c6a67cce 143
ayu13 0:83b2c6a67cce 144 timer.reset();
ayu13 0:83b2c6a67cce 145 }
ayu13 0:83b2c6a67cce 146 wait_us(10);
ayu13 0:83b2c6a67cce 147 }
ayu13 0:83b2c6a67cce 148 }
ayu13 0:83b2c6a67cce 149
ayu13 0:83b2c6a67cce 150 ///////////////// 関数宣言部分 //////////////////////
ayu13 0:83b2c6a67cce 151 double servoDeg(double servo_value)
ayu13 0:83b2c6a67cce 152 {
ayu13 0:83b2c6a67cce 153 return (servo_value - 3500)*270/(11500 - 3500);
ayu13 0:83b2c6a67cce 154 }
ayu13 2:b728a6564520 155 double degToRad(double x)
ayu13 2:b728a6564520 156 {
ayu13 2:b728a6564520 157 return x*M_PI/180;
ayu13 5:4fba3e91741f 158 }
ayu13 5:4fba3e91741f 159 void touchGrab()
ayu13 5:4fba3e91741f 160 {
ayu13 5:4fba3e91741f 161 if(ts_c1 == 0) { //タッチセンサ反応したらハンドルを掴む
ayu13 5:4fba3e91741f 162 wait_us(50);
ayu13 5:4fba3e91741f 163 if(ts_c1 == 0) {
ayu13 5:4fba3e91741f 164 servo_c.set_degree(0,servoDeg(deg_c_grab)); //servo_c掴む
ayu13 5:4fba3e91741f 165 state++;
ayu13 5:4fba3e91741f 166 myled4=1; //LED4 点灯
ayu13 5:4fba3e91741f 167 }
ayu13 5:4fba3e91741f 168 }
ayu13 0:83b2c6a67cce 169 }