test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

main.cpp

Committer:
shimizuta
Date:
2019-03-04
Revision:
36:b0edccff7457
Parent:
35:b4e1b8f25cd7
Child:
37:e4b37af4d8c7

File content as of revision 36:b0edccff7457:

//NHK2019MR2 馬型機構プログラム.
//#define VSCODE
#ifdef VSCODE
#include <math.h>
#include <stdio.h>
#else
#include "mbed.h"
#include "pinnames.h"
#include "KondoServo.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"   //歩き方に関するファイル
#include "OverCome.h"
#include "change_walk.h"
////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。
const int kServoSpan_ms = 6;                   //サーボの送信間隔
const float kBetweenServoHalf_m = 0.034 * 0.5; //サーボ間の距離の半分
float kLegLength1[2] = {0.15, 0.15};
float kLegLength2[2] = {0.33, 0.34};
//サーボの正負と座標系の正負の補正.足で一セット。
const int kServoSign[2][2] = {{-1, -1}, {-1, -1}};
//欲しい座標系0度でのサーボのICSマネージャーの値
const double kServoValToDegree = 270.0 / (11500 - 3500); //ICSの値を度に変換
const double kOriginDegree[2][2] = {
    {
        (7300 - 3500) * kServoValToDegree,
        (6995 - 3500) * kServoValToDegree + 180,
    },
    {
        (7619 - 3500) * kServoValToDegree,
        (7085 - 3500) * kServoValToDegree + 180,
    },
};
///////////////
#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]),
};
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

FILE *fp;
const float kRadToDegree = 180.0 / M_PI;
int MoveOneCycle(Walk walkway, OneLeg leg[4]);
void MoveServo(OneLeg leg, int legnum, int servo_id);
void WaitStdin(char startchar);
int FileOpen();
////////調整するべきパラメータ
enum WalkWay
{
    STANDUP,
    LRFPOSTURE,
    FRONTLEG_ON_SANDDUNE, //前足かける
    TURNLEFT,
    TURNRIGHT,
    // MOVE_FRONTLEG_ON_SANDDUNE,
};

float offset_x_m[4] = {-0.1, 0.1, -0.1, 0.1},
      offset_y_m[4] = {0.35, 0.35, 0.35, 0.35};
//strideはLRFから変更するようにする
float stride_m[4] = {0.2, 0.2, 0.2, 0.2},
      height_m[4] = {0.1, 0.1, 0.1, 0.1}, buffer_height_m = 0.05,
      stridetime_s = 1, toptime_s = 0.4, buffer_time_s = 0.2;
/*
    LineParam over_come_front[]{
        {.time_s = 0, .x_m = -0.075, .y_m = 0.41},
        {.time_s = 0.2, .x_m = -0.175, .y_m = 0.26},
        {.time_s = 0.4, .x_m = 0.075, .y_m = 0.26},
        {.time_s = 0.6, .x_m = 0.075, .y_m = 0.41},
        {.time_s = 1.6, .x_m = -0.075, .y_m = 0.41},
    };
*/
float d_x_m = 0.1;
float start_y_m[4] = {0.41, 0.41, 0.41, 0.41};
float goal_y_m[4] = {0.41, 0.29, 0.41, 0.29};
float overcome_height_m[] = {0.1, 0.2, 0.1, 0.2};
float gravity_dist[] = {0.01, -0.01, 0.01, -0.01};
int SetWalk(Walk &walk, WalkWay way)
{
    switch (way)
    {
    case STANDUP:
        for (int i = 0; i < 4; i++)
            SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5);
        break;
    case LRFPOSTURE:
        for (int i = 0; i < 4; i++)
            SetOneLegTriangleParam(walk, i, offset_x_m[i], offset_y_m[i],
                                   stride_m[i], height_m[i], buffer_height_m,
                                   stridetime_s, toptime_s, buffer_time_s);
        walk.SetOffsetTime(0, 0.5, 0.5, 0);
        break;

    case FRONTLEG_ON_SANDDUNE: //前足かける
                               //                                   for(int q = 0; q < 4; q++)
                               //            SetOneLegFreeLinesParam(walk, q, over_come_front, sizeof(over_come_front) / sizeof(over_come_front[0]));
                               //        walk.SetOffsetTime(0, 0.5, 0.5, 0);

        OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg);
        walk.Copy(overcome.walk);
        break;
    case TURNLEFT:
        for (int i = 0; i < 4; i++)
            SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5);
        break;
    case TURNRIGHT:
        for (int i = 0; i < 4; i++)
            SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5);
        break;
    }
    return walk.CheckOrbit();
}

int main()
{
#ifdef VSCODE
    if (FileOpen()) //csv fileに書き込み
        return 1;   //異常終了したら強制終了
#endif
    OneLeg leg[4]; //各足の位置
    for (int i = 0; i < 4; i++)
        leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2);
    Walk walk(leg); //歩行法はここに入れていく
    Walk::calctime_s_ = 0.03;
    printf("Stand up?\r\n");
    WaitStdin('y'); // ボタンを押したら立つ
    if (SetWalk(walk, STANDUP) == 1)
    {
        printf("error: stand move\r\n");
        return 1; //強制終了.errorは内部の関数からprintfで知らせる
    }
    if (MoveOneCycle(walk, leg) == 1)
    {
        printf("error: stand move\r\n");
        return 1; //強制終了.errorは内部の関数からprintfで知らせる
    }
    printf("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();
            SetWalk(walk, LRFPOSTURE);
    MoveOneCycle(walk, leg);
    }
#else

    if (SetWalk(walk, FRONTLEG_ON_SANDDUNE) == 1)
    {
        printf("error: triangle\r\n");
        return 1; //強制終了.errorは内部の関数からprintfで知らせる
    }

    for (int i = 0; i < 2; i++)
    {
        if (MoveOneCycle(walk, leg) == 1)
        {
            printf("error: triangle move\r\n");
            return 1; //強制終了.errorは内部の関数からprintfで知らせる
        }
    }
    offset_y_m[LEFT_F] = 0.29;
    offset_y_m[RIGHT_F] = 0.29;
    if (SetWalk(walk, LRFPOSTURE) == 1)
    {
        printf("error: triangle\r\n");
        return 1; //強制終了.errorは内部の関数からprintfで知らせる
    }

    for (int i = 0; i < 20; i++)
    {
        if (MoveOneCycle(walk, leg) == 1)
        {
            printf("error: triangle move\r\n");
            return 1; //強制終了.errorは内部の関数からprintfで知らせる
        }
    }

    printf("program end\r\n");
#ifdef VSCODE
    fclose(fp);
#endif
#endif
}
//一サイクル分進む.return 1:異常終了
int MoveOneCycle(Walk walkway, OneLeg leg[4])
{
#ifndef VSCODE
    timer.reset();
    timer.start();
#endif
    int count = walkway.orbit[0].GetOneWalkTime() / walkway.calctime_s_;
    for (int i = 0; i < count; i++)
    {
#ifndef VSCODE
        float time_s = timer.read();
#endif
        //4本の足それぞれの足先サーボ角度更新
        if (walkway.Cal4LegsPosi(leg) == 1)
        {
            printf("error: time = %f\r\n", i * walkway.calctime_s_);
            return 1;
        }
#ifdef USE_CAN
        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);
#ifdef VSCODE
        //ファイルに書き込み。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");
#else
        //計算周期が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
        { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。
            DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s);
            led[0] = 1;
        }
#endif
    }
    return 0;
}
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);
    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;
    int state = cmd_vel.z;
    //閾値は要検討
    if (right_vel < left_vel)
    {
        stride_m[LEFT_F] = 0.2;
        stride_m[RIGHT_F] = 0.2;
        stride_m[LEFT_B] = 0.1;
        stride_m[RIGHT_B] = 0.1;
    }
    else
    {
        stride_m[LEFT_F] = 0.1;
        stride_m[RIGHT_F] = 0.1;
        stride_m[LEFT_B] = 0.2;
        stride_m[RIGHT_B] = 0.2;
    }

}
#endif