test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
Diff: main.cpp
- Revision:
- 43:2ed84f3558c1
- Parent:
- 42:982064594ba6
- Child:
- 44:4aac39b8670b
diff -r 982064594ba6 -r 2ed84f3558c1 main.cpp --- a/main.cpp Tue Mar 05 09:08:40 2019 +0000 +++ b/main.cpp Wed Mar 06 12:13:46 2019 +0000 @@ -1,19 +1,15 @@ //NHK2019MR2 馬型機構プログラム. -//#define VSCODE -#ifdef VSCODE +#include "pi.h" #include <math.h> #include <stdio.h> -#else +#ifndef VSCODE #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> -#include <std_msgs/Int16.h> +//#define USE_ROS //ROSを使うときはコメントアウトを外す +#include "ros.h" +#include "geometry_msgs/Vector3.h" +#include "std_msgs/Int16.h" #endif //#define DEBUG_ON //デバッグ用。使わないときはコメントアウト #include "debug.h" @@ -21,85 +17,64 @@ #include "Walk.h" //歩き方に関するファイル #include "OverCome.h" #include "change_walk.h" -////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。 -const int kServoSpan_ms = 6; //サーボの送信間隔 +#include "servo_and_movefunc.h" +enum ROS_STATE +{ + STOP, + RUN, + SANDDUNE, + ROPE_STATE +}; +int state_from_ros = 0; +#ifdef USE_ROS +ros::NodeHandle nh_mbed; +void callback(const geometry_msgs::Vector3 &cmd_vel); +void callback_state(const std_msgs::Int16 &cmd_vel); +ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback); +ros::Subscriber<std_msgs::Int16> sub_state("/state", &callback_state); +#endif +////////////あまり変化させないパラメーター 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] = { - { - (7268 - 3500) * kServoValToDegree, - (7768 - 3500) * kServoValToDegree + 180, - }, - { - (7914 - 3500) * kServoValToDegree, - (7543 - 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); -void callback_state(const std_msgs::Int16 &cmd_vel); -//LPからの左右速度比を受けとり、それをもとに歩行パターンを決定する -//1サイクルの間、通信は遮断され、サイクル終了後に通信を受け付ける -ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback); -ros::Subscriber<std_msgs::Int16> sub_state("/state", &callback_state); -// ros::Publisher<geometry_msgs::Vector3> pub_vel("/callback_vel"); -#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, + STANDUP, //受け渡し用に待つ LRFPOSTURE, //LRF用 + STANDUP_SANDDUNE, //段差前で立つ + BEFORE_SANDDUNE, //段差に壁当て FRONTLEG_ON_SANDDUNE, //前足を段差にかける OVERCOME, //前足が乗った状態で進む BACKLEG_ON_SANDDUNE, //後ろ脚を段差に載せる OVERCOME2, //後ろ脚が乗った状態で進む - CHECK, //check用に最後に置いておく + ROPE, //rope前足超える + ROPE_BACK, //rope後ろ足超える + ROPE_DOWN, //rope機体高さをLRF用に落とす + SLOPE, + CHECK, //check用に最後に置いておく }; //LRFPOSTUREだけspinOnceで変更するためグローバルで float offset_x_m[4] = {-0.15, 0.15, -0.15, 0.15}, - offset_y_m[4] = {0.35, 0.35, 0.35, 0.35}; -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.2, buffer_time_s = 0.2; - -int state_from_ros = 0; // -enum ROS_STATE + offset_y_m[4] = {0.27, 0.27, 0.27, 0.27}; +float stride_m[4] = {0.2, 0.2, 0.2, 0.2}; //ropeのときは0.15だった +float height_m[4] = {0.05, 0.05, 0.05, 0.05}, buffer_height_m = 0.02, + stridetime_s = 1, toptime_s = 0.2, buffer_time_s = 0.1; +int SetWalk(Walk &walk, WalkWay way) //歩行パラメータの事前セット { - RUN, - SANDDUNE, - ROPE -}; -int SetWalk(Walk &walk, WalkWay way) -{ + float overcome_start_y_m[] = {0.41, 0.41, 0.41, 0.41}; switch (way) { - case STANDUP: //LRF用に変数はグローバルにある + case STANDUP: + { //受け渡し用に待つ + float offset_x_m[4] = {}, + offset_y_m[4] = {0.3, 0.3, 0.3, 0.3}; for (int i = 0; i < 4; i++) - SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 10); + SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5); + walk.SetOffsetTime(0, 0, 0, 0); break; + } case LRFPOSTURE: //LRF用に変数はグローバルにある for (int i = 0; i < 4; i++) SetOneLegTriangleParam(walk, i, offset_x_m[i], offset_y_m[i], @@ -107,33 +82,61 @@ stridetime_s, toptime_s, buffer_time_s); walk.SetOffsetTime(0, 0.5, 0.5, 0); break; - case FRONTLEG_ON_SANDDUNE: //前足を段差にかける + case BEFORE_SANDDUNE: + { + float stride_short_m[] = {0.1, 0.1, 0.1, 0.1}; + for (int i = 0; i < 4; i++) + SetOneLegTriangleParam(walk, i, offset_x_m[i], overcome_start_y_m[i], + stride_short_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 STANDUP_SANDDUNE: { + float start_y_m[4] = {0.41, 0.41, 0.41, 0.41}; + for (int i = 0; i < 4; i++) + { + LineParam lines[] = { + {.time_s = 0, .x_m = walk.leg[i].GetX_m(), .y_m = walk.leg[i].GetY_m(), .is_point_to_point = 0}, + {.time_s = 0.5, .x_m = offset_x_m[i], .y_m = start_y_m[i], .is_point_to_point = 0}, + {.time_s = 1.5, .x_m = offset_x_m[i], .y_m = start_y_m[i], .is_point_to_point = 0}, + }; + SetOneLegFreeLinesParam(walk, i, lines, sizeof(lines) / sizeof(lines[0])); + } + walk.SetOffsetTime(0, 0, 0, 0); + } + break; + case FRONTLEG_ON_SANDDUNE: + { //前足を段差にかける 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 raise_offset_x_m[4] = {0, -0.02, 0, 0}; float overcome_height_m[] = {0.1, 0.2, 0.1, 0.2}; float gravity_dist[] = {0.05, 0, 0.05, -0.05}; - OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg); + OverCome overcome(offset_x_m, overcome_start_y_m, d_x_m, goal_y_m, + overcome_height_m, gravity_dist, walk.leg, raise_offset_x_m); walk.Copy(overcome.walk); break; } - case BACKLEG_ON_SANDDUNE: //後ろ脚を乗せる - { + case BACKLEG_ON_SANDDUNE: + { //後ろ脚を乗せる float d_x_m = 0.1; - float start_x_m[4] = {0, -0.08, 0, -0.08}; + float start_x_m[4] = {0, 0, 0, 0}; float start_y_m[4] = {0.41, 0.41, 0.41, 0.41}; float goal_y_m[4] = {0.29, 0.41, 0.29, 0.41}; + float raise_offset_x_m[4] = {}; float overcome_height_m[] = {0.2, 0.1, 0.2, 0.1}; - float gravity_dist[] = {0.15, 0, 0.05, -0.05}; - OverCome overcome(start_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg); + float gravity_dist[] = {0.1, 0, 0.1, 0}; + OverCome overcome(start_x_m, start_y_m, d_x_m, goal_y_m, + overcome_height_m, gravity_dist, walk.leg, raise_offset_x_m); walk.Copy(overcome.walk); break; } - case OVERCOME: //前足が乗った状態で進む - { + case OVERCOME: + { //前足が乗った状態で進む float offset_x_m[4] = {-0.15, 0.15, -0.15, 0.15}, - offset_y_m[4] = {0.35, 0.35, 0.35, 0.35}; + offset_y_m[4] = {0.38, 0.35, 0.38, 0.35}; 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.2, buffer_time_s = 0.2; @@ -144,8 +147,8 @@ walk.SetOffsetTime(0, 0.5, 0.5, 0); break; } - case OVERCOME2: //後ろ脚が乗った状態で進む - { + case OVERCOME2: + { //後ろ脚が乗った状態で進む float offset_x_m[4] = {}, offset_y_m[4] = {0.35, 0.35, 0.35, 0.35}; float stride_m[4] = {0.2, 0.2, 0.2, 0.2}, @@ -158,14 +161,91 @@ walk.SetOffsetTime(0, 0.5, 0.5, 0); break; } + case ROPE: + { + /* + float offset_x_m[4] = {-0.10, -0.10, -0.10, -0.10}, + offset_y_m[4] = {0.45, 0.45, 0.45, 0.45}, + stride_m[4] = {0.1, 0.1, 0.1, 0.1}, + height_m[4] = {0.17, 0.17, 0.17, 0.17}, buffer_height_m = 0.15, + stridetime_s = 1, toptime_s = 0.2, buffer_time_s = 0.2; + for (int i = 0; i < 4; i++) + SetOneLegFourPointParam(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);*/ + /* + LineParam over_come_front[] = { + {.time_s = 0, .x_m = -0.05, .y_m = 0.45, .is_point_to_point = 0}, + {.time_s = 0.5, .x_m = -0.15, .y_m = 0.45, .is_point_to_point = 0}, + {.time_s = 1, .x_m = -0.2366, .y_m = 0.3, .is_point_to_point = 0}, + {.time_s = 1.5, .x_m = -0.037, .y_m = 0.3, .is_point_to_point = 1}, + {.time_s = 2, .x_m = -0.05, .y_m = 0.45, .is_point_to_point = 0}, + }; + for (int i = 0; i < 4; i++) + SetOneLegFreeLinesParam(walk, i, over_come_front, sizeof(over_come_front) / sizeof(over_come_front[0])); + walk.SetOffsetTime(0, 0.5, 0.5, 0); + */ + float offset_x_m[4] = {-0.05, 0, -0.05, 0}; + float d_x_m = 0.2; + float start_y_m[4] = {0.41, 0.41, 0.41, 0.41}; + float goal_y_m[4] = {0.41, 0.41, 0.41, 0.41}; + float raise_offset_x_m[] = {0, -0.08, 0, -0.08}; + float overcome_height_m[] = {0.05, 0.2, 0.05, 0.2}; + float gravity_dist[] = {0.05, -0.05, 0.05, -0.05}; + OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, + overcome_height_m, gravity_dist, walk.leg, raise_offset_x_m); + walk.Copy(overcome.walk); + } + break; + case ROPE_BACK: + { + + float offset_x_m[4] = {}; + float d_x_m = 0.15; + float start_y_m[4] = {0.41, 0.41, 0.41, 0.41}; + float goal_y_m[4] = {0.41, 0.41, 0.41, 0.41}; + float raise_offset_x_m[] = {-0.03, 0, -0.03, 0}; + float overcome_height_m[] = {0.2, 0.05, 0.2, 0.05}; + float gravity_dist[] = {0.08, 0, 0.08, 0}; + OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, + overcome_height_m, gravity_dist, walk.leg, raise_offset_x_m); + walk.Copy(overcome.walk); + } + break; + case ROPE_DOWN: + { + for (int i = 0; i < 4; i++) + { + LineParam lines[] = { + {.time_s = 0, .x_m = walk.leg[i].GetX_m(), .y_m = walk.leg[i].GetY_m(), .is_point_to_point = 0}, + {.time_s = 0.5, .x_m = offset_x_m[i], .y_m = offset_y_m[i], .is_point_to_point = 0}, + }; + SetOneLegFreeLinesParam(walk, i, lines, sizeof(lines) / sizeof(lines[0])); + } + walk.SetOffsetTime(0, 0, 0, 0); + } + break; + case SLOPE: + { + float offset_x_m[4] = {-0.15, 0.15, -0.15, 0.15}, + offset_y_m[4] = {0.32, 0.22, 0.32, 0.22}; + float stride_m[4] = {0.18, 0.18, 0.2, 0.2}; //ropeのときは0.15 + float height_m[4] = {0.05, 0.05, 0.05, 0.05}, buffer_height_m = 0.02, + stridetime_s = 1, toptime_s = 0.2, buffer_time_s = 0.1; + 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; default: printf("error: there is no WalkWay\r\n"); return 1; } - return walk.CheckOrbit(); } - int main() { #ifdef VSCODE @@ -185,31 +265,82 @@ return 1; //強制終了.errorは内部の関数からprintfで知らせる } } + // SetWalk(walk, STANDUP); + SetWalk(walk, STANDUP_SANDDUNE); +#ifndef USE_ROS printf("Stand up?\r\n"); WaitStdin('y'); // ボタンを押したら立つ - if (SetWalk(walk, STANDUP) == 1) +#endif + MoveOneCycle(walk, leg); +#ifndef USE_ROS + printf("Move?\r\n"); + WaitStdin('y'); // ボタンを押したら立つ +#endif +/* + + WaitStdin('y'); // ボタンを押したらスタート + if (SetWalk(walk, SLOPE) == 1) { - printf("error: stand move\r\n"); - return 1; //強制終了.errorは内部の関数からprintfで知らせる + printf("error: LRFPOSTURE\r\n"); + return 1; //強制終了. } - MoveOneCycle(walk, leg); - printf("Move?\r\n"); - WaitStdin('y'); // ボタンを押したらスタート + for (int i = 0; i < 30; i++) + MoveOneCycle(walk, leg); +*/ +/* + /////////////ROPEを試す + if (SetWalk(walk, ROPE) == 1) + { + printf("error: ROPE\r\n"); + return 1; //強制終了. + } + MoveOneCycle(walk, leg); + if (SetWalk(walk, ROPE_DOWN) == 1) + { + printf("error: ROPE_DOWN\r\n"); + return 1; //強制終了. + } + MoveOneCycle(walk, leg); + if (SetWalk(walk, LRFPOSTURE) == 1) + { + printf("error: LRFPOSTURE\r\n"); + return 1; //強制終了. + } + for (int i = 0; i < 3; i++) + MoveOneCycle(walk, leg); + + if (SetWalk(walk, ROPE_BACK) == 1) + { + printf("error:ROPE_BACK \r\n"); + return 1; //強制終了. + } + MoveOneCycle(walk, leg); + */ #ifdef USE_ROS nh_mbed.getHardware()->setBaud(115200); nh_mbed.initNode(); nh_mbed.subscribe(sub_vel); nh_mbed.subscribe(sub_state); nh_mbed.spinOnce(); //一度受信 + SetWalk(walk, LRFPOSTURE); while (1) { - - SetWalk(walk, LRFPOSTURE); - MoveOneCycle(walk, leg); - nh_mbed.spinOnce(); - if (state_from_ros = SANDDUNE) + switch (state_from_ros) { + case STOP: + break; + case RUN: + 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); + MoveOneCycle(walk, leg); + break; + case SANDDUNE: #endif + //2歩進んで当て処理 + // for (int i = 0; i < 2; i++) + // MoveOneCycle(walk, leg); //前足を段差にかける if (SetWalk(walk, FRONTLEG_ON_SANDDUNE) == 1) { @@ -240,10 +371,12 @@ printf("error: triangle\r\n"); return 1; //強制終了. } - for (int i = 0; i < 5; i++) + for (int i = 0; i < 3; i++) MoveOneCycle(walk, leg); #ifdef USE_ROS + break; } + nh_mbed.spinOnce(); } #endif printf("program end\r\n"); @@ -251,97 +384,20 @@ fclose(fp); #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) { + // pub_vel.publish(&cmd_vel); + if (state_from_ros == 0) + state_from_ros = 1; stride_m[LEFT_F] = cmd_vel.x; stride_m[LEFT_B] = cmd_vel.x; stride_m[RIGHT_F] = cmd_vel.y; stride_m[RIGHT_B] = cmd_vel.y; } -void callback_state(const std_msgs::Int16 &cmd_vel) +void callback_state(const std_msgs::Int16 &cmd) { - state_from_ros = cmd_vel.data; + state_from_ros = cmd.data; + led[state_from_ros] = 1; } #endif \ No newline at end of file