test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
main.cpp
- Committer:
- shimizuta
- Date:
- 2019-03-06
- Revision:
- 43:2ed84f3558c1
- Parent:
- 42:982064594ba6
- Child:
- 44:4aac39b8670b
File content as of revision 43:2ed84f3558c1:
//NHK2019MR2 馬型機構プログラム. #include "pi.h" #include <math.h> #include <stdio.h> #ifndef VSCODE #include "mbed.h" #include "pinnames.h" #include "can.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" #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。 #include "Walk.h" //歩き方に関するファイル #include "OverCome.h" #include "change_walk.h" #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}; /////////////// ////////調整するべきパラメータ enum WalkWay { STANDUP, //受け渡し用に待つ LRFPOSTURE, //LRF用 STANDUP_SANDDUNE, //段差前で立つ BEFORE_SANDDUNE, //段差に壁当て FRONTLEG_ON_SANDDUNE, //前足を段差にかける OVERCOME, //前足が乗った状態で進む BACKLEG_ON_SANDDUNE, //後ろ脚を段差に載せる OVERCOME2, //後ろ脚が乗った状態で進む 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.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) //歩行パラメータの事前セット { float overcome_start_y_m[] = {0.41, 0.41, 0.41, 0.41}; switch (way) { 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], 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], 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 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 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, 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: { //後ろ脚を乗せる float d_x_m = 0.1; 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.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: { //前足が乗った状態で進む float offset_x_m[4] = {-0.15, 0.15, -0.15, 0.15}, 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; 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); break; } 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}, 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; 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); 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 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; for (int i = 0; i < CHECK; i++) { if (SetWalk(walk, (WalkWay)i) == 1) { printf("error: move %d\r\n", i); return 1; //強制終了.errorは内部の関数からprintfで知らせる } } // SetWalk(walk, STANDUP); SetWalk(walk, STANDUP_SANDDUNE); #ifndef USE_ROS printf("Stand up?\r\n"); WaitStdin('y'); // ボタンを押したら立つ #endif MoveOneCycle(walk, leg); #ifndef USE_ROS printf("Move?\r\n"); WaitStdin('y'); // ボタンを押したら立つ #endif /* WaitStdin('y'); // ボタンを押したらスタート if (SetWalk(walk, SLOPE) == 1) { printf("error: LRFPOSTURE\r\n"); return 1; //強制終了. } 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) { 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) { printf("error: triangle\r\n"); return 1; //強制終了. } for (int i = 0; i < 1; i++) MoveOneCycle(walk, leg); //前足が段差に乗った状態で進む if (SetWalk(walk, OVERCOME) == 1) { printf("error: triangle\r\n"); return 1; //強制終了. } for (int i = 0; i < 5; i++) MoveOneCycle(walk, leg); //後ろ脚載せる if (SetWalk(walk, BACKLEG_ON_SANDDUNE) == 1) { printf("error: triangle\r\n"); return 1; //強制終了. } for (int i = 0; i < 1; i++) MoveOneCycle(walk, leg); //後ろ脚乗った状態で進む if (SetWalk(walk, OVERCOME2) == 1) { printf("error: triangle\r\n"); return 1; //強制終了. } for (int i = 0; i < 3; i++) MoveOneCycle(walk, leg); #ifdef USE_ROS break; } nh_mbed.spinOnce(); } #endif printf("program end\r\n"); #ifdef VSCODE fclose(fp); #endif } #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) { state_from_ros = cmd.data; led[state_from_ros] = 1; } #endif