test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

Revision:
27:79b4b932a6dd
Parent:
21:61971fc18b90
Child:
28:8e1cbeffe6c2
--- a/main.cpp	Fri Feb 22 05:20:28 2019 +0000
+++ b/main.cpp	Wed Feb 27 01:24:00 2019 +0000
@@ -1,37 +1,38 @@
 //NHK2019MR2 馬型機構プログラム.
+#define VSCODE
+#ifdef VSCODE
+#define _USE_MATH_DEFINES
+#include <math.h>
+#include <stdio.h>
+#else
 #include "mbed.h"
 #include "pinnames.h"
 #include "KondoServo.h"
-//#define DEBUG_ON//デバッグ用。使わないときはコメントアウト
-#include "debug.h"
 #include "pi.h"
 #include "can.h"
+#define USE_CAN //can通信するならdefine.しないなら切らないとエラー出る
+#define USE_ROS
+#include <ros.h>
+#include <geometry_msgs/Vector3.h>
+#endif
+//#define DEBUG_ON //デバッグ用。使わないときはコメントアウト
+#include "debug.h"
 #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。
 #include "Walk.h"   //歩き方に関するファイル
-#define USE_CAN     //can通信するならdefine.しないなら切らないとエラー出る
 
-////////////調整すべきパラメータ.全てここに集めた。
-const float kCycleTime_s = 0.03;              //計算周期
+////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。
+const int kServoSpan_ms = 6;                  //サーボの送信間隔
 const float kBetweenServoHalf_m = 0.03 * 0.5; //サーボ間の距離の半分
 float kLegLength1[2] = {0.1, 0.1};
 float kLegLength2[2] = {0.2452 + 0.0025, 0.22529 + 0.0025};
-//サーボの設定
-const int kServoSpan_ms = 10; //サーボの送信間隔
-const double kServoValToDegree = 270.0 / (11500 - 3500);
 //サーボの正負と座標系の正負の補正.足で一セット。
-const int kServoSign[2][2] = {{
-                                  1,
-                                  -1,
-                              },
-                              {
-                                  -1,
-                                  1,
-                              }};
+const int kServoSign[2][2] = {{1, -1}, {-1, 1}};
 //欲しい座標系0度でのサーボのICSマネージャーの値
+const double kServoValToDegree = 270.0 / (11500 - 3500); //ICSの値を度に変換
 const double kOriginDegree[2][2] = {
     {
-        (7257 - 3500) * kServoValToDegree,
-        (6590 - 3500) * kServoValToDegree + 180,
+        (8338 - 3500) * kServoValToDegree,
+        (5887 - 3500) * kServoValToDegree + 180,
     },
     {
         (6470 - 3500) * kServoValToDegree,
@@ -39,118 +40,148 @@
     },
 };
 ///////////////
+#ifndef VSCODE
 Timer timer;
 KondoServo servo[2] = {
     KondoServo(pin_serial_servo_tx[0], pin_serial_servo_rx[0]),
     KondoServo(pin_serial_servo_tx[1], pin_serial_servo_rx[1]),
 };
-//足の作成、サイズデータのみの足の骨組
-OneLeg leg[4] = {
-    OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2),
-    OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2),
-    OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2),
-    OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2),
+DigitalOut led[4] = {DigitalOut(LED1), DigitalOut(LED2), DigitalOut(LED3), DigitalOut(LED4)};
+#endif
+#ifdef USE_ROS
+ros::NodeHandle nh_mbed;
+//ROSからのコールバック関数
+void callback(const geometry_msgs::Vector3 &cmd_vel);
+//LPからの左右速度比を受けとり、それをもとに歩行パターンを決定する
+//1サイクルの間、通信は遮断され、サイクル終了後に通信を受け付ける
+ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback);
+#endif
+OneLeg leg[4]; //各足の位置
+enum LegNum    //足とシリアルサーボの番号
+{
+    RIGHT_B,
+    RIGHT_F,
+    LEFT_B,
+    LEFT_F,
 };
-DigitalOut led[4] = {DigitalOut(LED1), DigitalOut(LED2), DigitalOut(LED3), DigitalOut(LED4)};
-
+FILE *fp;
 const float kRadToDegree = 180.0 / M_PI;
-void Move(Walk walkway, OneLeg (&leg)[4], float dist_m);
+void MoveOneCycle(Walk walkway, OneLeg leg[4]);
 void MoveServo(OneLeg leg, int legnum, int servo_id);
-int IsArrived(int count, int finish)
+void WaitStdin(char startchar);
+int FileOpen();
+int IsArrived(int count, int finish);
+
+////////調整するべきパラメータ
+enum WalkWay
+{
+    STANDUP,
+    STRAIGHT,
+    TURNLEFT,
+    TURNRIGHT,
+    END,
+};
+void ParamsSetup(Walk walks[END], OneLeg leg[4]) //各パラメータの設定。減らしていく必要あり
 {
-    if (count > finish)
-        return 1;
-    else
-        return 0;
+    Walk::calctime_s_ = 0.03; //計算周期
+    //足の作成、サイズデータのみの足の骨組.4足同じにしている
+    for (int i = 0; i < 4; i++)
+        leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2);
+    //軌道のデフォルト値
+    const float kStrideTime_s = 0.3, kRiseTime_s = 0.1,
+                kStride_m = 0.15, kHeight_m = 0.03, kGround_m = 0.2,
+                kEllipseCenterX_m = 0, kEllipseCenterY_m = kGround_m;
+    //STANDUP時のパラメータ。
+    walks[STANDUP].SetAllLegStandParam(0, 0.2, 0.5); //一括で設定できる
+
+    //STRAIGHT1のparamater
+    walks[STRAIGHT].SetOffset(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
+    walks[STRAIGHT].SetAllLegEllipseParam      // 4足一括で設定
+        (kStrideTime_s, kRiseTime_s, kStride_m, kHeight_m, kGround_m, kEllipseCenterX_m, kEllipseCenterY_m);
+
+    //TURNLEFT1のparam
+    float stridetime_s = 0.2, risetime_s = 0.1, stride_short_m = 0.2, stride_long_m = 0.1;
+    walks[TURNLEFT].SetAllLegEllipseParam // 4足を取り敢えず一括で設定してから
+        (stridetime_s, risetime_s, stride_short_m, kHeight_m, kGround_m, 0, kEllipseCenterY_m);
+    walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更
+    walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_long_m);
+    walks[TURNLEFT].SetOffset(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
+
+    //TURNRIGHT1のparam
+    walks[TURNRIGHT].SetAllLegEllipseParam // 4足を取り敢えず一括で設定してから
+        (stridetime_s, risetime_s, stride_short_m, kHeight_m, kGround_m, 0, kEllipseCenterY_m);
+    walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更
+    walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_long_m);
+    walks[TURNRIGHT].SetOffset(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
 }
+Walk walks[END]; //歩行法
 int main()
 {
-    printf("When you push any key, this robot starts.\r\n");
-    while (pc.readable() == 0) //キーボード押したらスタート
-        ;
-    printf("stand up for 1 s\r\n");
-
-    //stand時の足の軌道設定.
-    Orbit stand_orbit[4];
-    float stand_ground_m = 0.2;
-    stand_orbit[0].SetStandParam(stand_ground_m);
-    for (int i = 0; i < 4; i++) //全部足を同じにしてる
-        stand_orbit[i] = stand_orbit[0];
-    //4足の位相ずれOffsetTime_sをまとめる
-    float stand_offset_time_s[4] = {
-        0,
-        stand_orbit[0].GetOneWalkTime() * 0.5,
-        stand_orbit[0].GetOneWalkTime() * 0,
-        stand_orbit[0].GetOneWalkTime() * 0.5,
-    };
-    //4つの足のorbit, 位相を代入してstraightという歩行パターンを作成している
-    //このインスタンスはlegそれぞれの計算を行う役割を担う
-    //orbitはここでしか使わないあくまでパラメータ設定用クラス
-    Walk stand(stand_orbit, stand_offset_time_s, kCycleTime_s);
-    float dist_m = 10; //収束判定用。現在は回すループの数
-    //動作開始
-    Move(stand, leg, dist_m);
-    wait(1);
-
-    DEBUG("move start\r\n");
-    //取り敢えず歩行したパラメータ
-    //stridetime_s = 0.5, risetime_s = 0.3,stride_m= 0.12f, height_m = 0.03f, ellipse_center_x_m  = 0, ellipse_center_y_m = 0.16f;
-    //曲げてみる
-    float stridetime_s = 2, risetime_s = 0.5,
-          stride_r_m = 0.1, stride_l_m = 0.05, height_m = 0.03, ground_m = stand_ground_m,
-          ellipse_center_x_m = -0.05, ellipse_center_y_m = ground_m;
-    //軌道の作成
-    //代入用の軌道SetStraightParam関数を用いると真っ直ぐ進む前提となる
-    Orbit orbit[4];
-    orbit[0].SetStraightParam(stridetime_s, risetime_s, stride_r_m, height_m, ground_m, ellipse_center_x_m, ellipse_center_y_m);
-    orbit[1].SetStraightParam(stridetime_s, risetime_s, stride_r_m, height_m, ground_m, 0, ellipse_center_y_m);
-    orbit[2].SetStraightParam(stridetime_s, risetime_s, stride_l_m, height_m, ground_m, ellipse_center_x_m, ellipse_center_y_m);
-    orbit[3].SetStraightParam(stridetime_s, risetime_s, stride_l_m, height_m, ground_m, 0, ellipse_center_y_m);
-    //4足の軌道と位相ずれOffsetTime_sをまとめる
-    float offset_time_s[4] = {
-        0,
-        orbit[0].GetOneWalkTime() * 0.5,
-        orbit[0].GetOneWalkTime() * 0.5,
-        orbit[0].GetOneWalkTime() * 0,
-    };
-    //4つの足のorbit, 位相を代入して歩行パターンを作成している
-    //このインスタンスはlegそれぞれの計算を行う役割を担う
-    //orbitはここでしか使わないあくまで鍵のような扱い
-    Walk walk(orbit, offset_time_s, kCycleTime_s);
-    dist_m = 500000; //収束判定用。取り敢えず今はループ数。
-    //動く
-    Move(walk, leg, dist_m);
-    DEBUG("program end\r\n");
+    if (FileOpen()) //csv fileに書き込み
+        return 1;   //異常終了したら強制終了
+    DEBUG("param set start");
+    ParamsSetup(walks, leg);      //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む
+    for (int i = 0; i < END; i++) //軌道のチェック
+    {
+        if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら
+            return 1;                         //強制終了.errorは内部の関数からprintfで知らせる
+    }
+    DEBUG("Stand up?\r\n");
+    WaitStdin('y'); // ボタンを押したら立つ
+    MoveOneCycle(walks[STANDUP], leg);
+    DEBUG("Move?\r\n");
+    WaitStdin('y'); // ボタンを押したらスタート
+#ifdef USE_ROS
+    nh_mbed.getHardware()->setBaud(115200);
+    nh_mbed.initNode();
+    nh_mbed.subscribe(sub_vel);
+    while (1)
+        nh_mbed.spinOnce();
+#else
+    for (int i = 1; i < END; i++) //ENDになるまでWalkWayの順に動作
+    {
+        DEBUG("Move %d\r\n", i);
+        for (int j = 0; j < 2; j++) //debug用に2歩進む
+            MoveOneCycle(walks[i], leg);
+    }
+    MoveOneCycle(walks[STANDUP], leg); //最後はLRFを保護するためSTANDUPの状態で終わる
+    printf("program end\r\n");
+    fclose(fp);
+#endif
 }
-
-//到達判定が来ない間,同じ歩行方法でループ.関数に入る前の足の位置を一切考慮しない点に注意
-void Move(Walk walkway, OneLeg (&leg)[4], float dist_m)
+//一サイクル分進む
+void MoveOneCycle(Walk walkway, OneLeg leg[4])
 {
+#ifndef VSCODE
     timer.reset();
     timer.start();
-    int is_arrived = 0;
-    int count = 0;
-    while (is_arrived == 0)
+#endif
+    int count = walkway.GetOneWalkTime() / walkway.calctime_s_;
+    for (int i = 0; i < count; i++)
     {
+#ifndef VSCODE
         float time_s = timer.read();
-        //注:未実装。到着したかの判定.LRFからのデータが必要.今は取り敢えずループ回数で判断
-        is_arrived = IsArrived(count, (int)dist_m);
-        ++count;
-        //4本の足それぞれの足先サーボ角度更新
-        walkway.Cal4LegsPosi(leg);
+#endif
+        walkway.Cal4LegsPosi(leg); //4本の足それぞれの足先サーボ角度更新
 #ifdef USE_CAN
-        //slave_mbed分の足の目標位置を送信
-        SendRad(leg[2], leg[3]);
+        SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信
 #endif
         //自身が動かす足のサーボを動かす
         MoveServo(leg[0], 0, 0);
         MoveServo(leg[1], 1, 0);
+#ifndef VSCODE
         wait_ms(kServoSpan_ms);
+#endif
         MoveServo(leg[0], 0, 1);
         MoveServo(leg[1], 1, 1);
-        DEBUG("%f, %f, %f, %f\r\n", leg[2].GetRad(0), leg[2].GetRad(1), leg[3].GetRad(0), leg[3].GetRad(1));
-        //計算周期がwalkway.cycletime_s_になるようwait
-        float rest_time_s = walkway.cycletime_s_ - (timer.read() - time_s);
+        //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順
+        fprintf(fp, "%f", i * walkway.calctime_s_);
+        for (int i = 0; i < 4; i++)
+            fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m());
+        fprintf(fp, "\r\n");
+#ifndef VSCODE
+        //計算周期がwalkway.calctime_s_になるようwait
+        float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s);
         if (rest_time_s > 0)
             wait(rest_time_s);
         else
@@ -158,13 +189,51 @@
             DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s);
             led[0] = 1;
         }
+#endif
     }
 }
 void MoveServo(OneLeg leg, int serial_num, int servo_id)
 {
+#ifndef VSCODE
     float degree = leg.GetRad(servo_id) * kRadToDegree;
     //サーボの座標系に変更
     float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id];
-    DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree);
+    //    DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree);
     servo[serial_num].set_degree(servo_id, servo_degree);
+#endif
 }
+void WaitStdin(char startchar)
+{
+#ifndef USE_ROS
+    char str[255] = {};
+    do
+    {
+        printf("put '%c', then start\r\n", startchar);
+        scanf("%s", str);
+    } while (str[0] != startchar);
+#endif
+}
+int FileOpen() //1:異常終了
+{
+    if ((fp = fopen("data.csv", "w")) == NULL)
+    {
+        printf("error : FileSave()\r\n");
+        return 1;
+    }
+    fprintf(fp, "time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]\r\n");
+    return 0;
+}
+#ifdef USE_ROS
+void callback(const geometry_msgs::Vector3 &cmd_vel)
+{
+    float left_vel = cmd_vel.x;
+    float right_vel = cmd_vel.y;
+    //閾値は要検討
+    if (right_vel < left_vel)
+        MoveOneCycle(walks[TURNRIGHT], leg);
+    else if (left_vel < right_vel)
+        MoveOneCycle(walks[TURNLEFT], leg);
+    else
+        MoveOneCycle(walks[STRAIGHT], leg);
+}
+#endif