test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

Committer:
shimizuta
Date:
Tue Mar 05 09:08:40 2019 +0000
Revision:
42:982064594ba6
Parent:
41:38d79b6513c0
Child:
43:2ed84f3558c1
overcome ok

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimizuta 11:e81425872740 1 //NHK2019MR2 馬型機構プログラム.
shimizuta 28:8e1cbeffe6c2 2 //#define VSCODE
shimizuta 27:79b4b932a6dd 3 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 4 #include <math.h>
shimizuta 27:79b4b932a6dd 5 #include <stdio.h>
shimizuta 27:79b4b932a6dd 6 #else
yuto17320508 0:f000d896d188 7 #include "mbed.h"
shimizuta 9:905f93247688 8 #include "pinnames.h"
shimizuta 11:e81425872740 9 #include "KondoServo.h"
shimizuta 14:d7cb429946f4 10 #include "pi.h"
shimizuta 16:0069a56f11a3 11 #include "can.h"
shimizuta 27:79b4b932a6dd 12 #define USE_CAN //can通信するならdefine.しないなら切らないとエラー出る
shimizuta 42:982064594ba6 13 #define USE_ROS
shimizuta 34:89d701e15cdf 14 #include <ros.h>
shimizuta 34:89d701e15cdf 15 #include <geometry_msgs/Vector3.h>
shimizuta 42:982064594ba6 16 #include <std_msgs/Int16.h>
shimizuta 27:79b4b932a6dd 17 #endif
shimizuta 27:79b4b932a6dd 18 //#define DEBUG_ON //デバッグ用。使わないときはコメントアウト
shimizuta 27:79b4b932a6dd 19 #include "debug.h"
shimizuta 11:e81425872740 20 #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。
shimizuta 11:e81425872740 21 #include "Walk.h" //歩き方に関するファイル
shimizuta 35:b4e1b8f25cd7 22 #include "OverCome.h"
shimizuta 35:b4e1b8f25cd7 23 #include "change_walk.h"
shimizuta 27:79b4b932a6dd 24 ////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。
shimizuta 35:b4e1b8f25cd7 25 const int kServoSpan_ms = 6; //サーボの送信間隔
shimizuta 35:b4e1b8f25cd7 26 const float kBetweenServoHalf_m = 0.034 * 0.5; //サーボ間の距離の半分
shimizuta 35:b4e1b8f25cd7 27 float kLegLength1[2] = {0.15, 0.15};
shimizuta 35:b4e1b8f25cd7 28 float kLegLength2[2] = {0.33, 0.34};
shimizuta 14:d7cb429946f4 29 //サーボの正負と座標系の正負の補正.足で一セット。
shimizuta 35:b4e1b8f25cd7 30 const int kServoSign[2][2] = {{-1, -1}, {-1, -1}};
shimizuta 14:d7cb429946f4 31 //欲しい座標系0度でのサーボのICSマネージャーの値
shimizuta 27:79b4b932a6dd 32 const double kServoValToDegree = 270.0 / (11500 - 3500); //ICSの値を度に変換
shimizuta 14:d7cb429946f4 33 const double kOriginDegree[2][2] = {
shimizuta 14:d7cb429946f4 34 {
shimizuta 42:982064594ba6 35 (7268 - 3500) * kServoValToDegree,
shimizuta 42:982064594ba6 36 (7768 - 3500) * kServoValToDegree + 180,
shimizuta 14:d7cb429946f4 37 },
shimizuta 14:d7cb429946f4 38 {
shimizuta 42:982064594ba6 39 (7914 - 3500) * kServoValToDegree,
shimizuta 42:982064594ba6 40 (7543 - 3500) * kServoValToDegree + 180,
shimizuta 14:d7cb429946f4 41 },
shimizuta 14:d7cb429946f4 42 };
shimizuta 9:905f93247688 43 ///////////////
shimizuta 27:79b4b932a6dd 44 #ifndef VSCODE
shimizuta 9:905f93247688 45 Timer timer;
shimizuta 11:e81425872740 46 KondoServo servo[2] = {
shimizuta 11:e81425872740 47 KondoServo(pin_serial_servo_tx[0], pin_serial_servo_rx[0]),
shimizuta 11:e81425872740 48 KondoServo(pin_serial_servo_tx[1], pin_serial_servo_rx[1]),
shimizuta 11:e81425872740 49 };
shimizuta 27:79b4b932a6dd 50 DigitalOut led[4] = {DigitalOut(LED1), DigitalOut(LED2), DigitalOut(LED3), DigitalOut(LED4)};
shimizuta 27:79b4b932a6dd 51 #endif
shimizuta 27:79b4b932a6dd 52 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 53 ros::NodeHandle nh_mbed;
shimizuta 27:79b4b932a6dd 54 //ROSからのコールバック関数
shimizuta 27:79b4b932a6dd 55 void callback(const geometry_msgs::Vector3 &cmd_vel);
shimizuta 42:982064594ba6 56 void callback_state(const std_msgs::Int16 &cmd_vel);
shimizuta 27:79b4b932a6dd 57 //LPからの左右速度比を受けとり、それをもとに歩行パターンを決定する
shimizuta 27:79b4b932a6dd 58 //1サイクルの間、通信は遮断され、サイクル終了後に通信を受け付ける
shimizuta 27:79b4b932a6dd 59 ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback);
shimizuta 42:982064594ba6 60 ros::Subscriber<std_msgs::Int16> sub_state("/state", &callback_state);
shimizuta 42:982064594ba6 61 // ros::Publisher<geometry_msgs::Vector3> pub_vel("/callback_vel");
shimizuta 27:79b4b932a6dd 62 #endif
shimizuta 34:89d701e15cdf 63
shimizuta 42:982064594ba6 64 FILE *fp;
shimizuta 11:e81425872740 65 const float kRadToDegree = 180.0 / M_PI;
shimizuta 32:dc684a0b8448 66 int MoveOneCycle(Walk walkway, OneLeg leg[4]);
shimizuta 11:e81425872740 67 void MoveServo(OneLeg leg, int legnum, int servo_id);
shimizuta 27:79b4b932a6dd 68 void WaitStdin(char startchar);
shimizuta 27:79b4b932a6dd 69 int FileOpen();
shimizuta 27:79b4b932a6dd 70 ////////調整するべきパラメータ
shimizuta 27:79b4b932a6dd 71 enum WalkWay
shimizuta 27:79b4b932a6dd 72 {
shimizuta 27:79b4b932a6dd 73 STANDUP,
shimizuta 42:982064594ba6 74 LRFPOSTURE, //LRF用
shimizuta 42:982064594ba6 75 FRONTLEG_ON_SANDDUNE, //前足を段差にかける
shimizuta 42:982064594ba6 76 OVERCOME, //前足が乗った状態で進む
shimizuta 42:982064594ba6 77 BACKLEG_ON_SANDDUNE, //後ろ脚を段差に載せる
shimizuta 42:982064594ba6 78 OVERCOME2, //後ろ脚が乗った状態で進む
shimizuta 42:982064594ba6 79 CHECK, //check用に最後に置いておく
shimizuta 27:79b4b932a6dd 80 };
shimizuta 42:982064594ba6 81 //LRFPOSTUREだけspinOnceで変更するためグローバルで
shimizuta 42:982064594ba6 82 float offset_x_m[4] = {-0.15, 0.15, -0.15, 0.15},
shimizuta 35:b4e1b8f25cd7 83 offset_y_m[4] = {0.35, 0.35, 0.35, 0.35};
shimizuta 35:b4e1b8f25cd7 84 float stride_m[4] = {0.2, 0.2, 0.2, 0.2},
shimizuta 42:982064594ba6 85 height_m[4] = {0.1, 0.1, 0.1, 0.1}, buffer_height_m = 0.05,
shimizuta 42:982064594ba6 86 stridetime_s = 1, toptime_s = 0.2, buffer_time_s = 0.2;
shimizuta 42:982064594ba6 87
shimizuta 42:982064594ba6 88 int state_from_ros = 0; //
shimizuta 42:982064594ba6 89 enum ROS_STATE
shimizuta 42:982064594ba6 90 {
shimizuta 42:982064594ba6 91 RUN,
shimizuta 42:982064594ba6 92 SANDDUNE,
shimizuta 42:982064594ba6 93 ROPE
shimizuta 42:982064594ba6 94 };
shimizuta 35:b4e1b8f25cd7 95 int SetWalk(Walk &walk, WalkWay way)
shimizuta 35:b4e1b8f25cd7 96 {
shimizuta 35:b4e1b8f25cd7 97 switch (way)
shimizuta 35:b4e1b8f25cd7 98 {
shimizuta 42:982064594ba6 99 case STANDUP: //LRF用に変数はグローバルにある
shimizuta 35:b4e1b8f25cd7 100 for (int i = 0; i < 4; i++)
shimizuta 42:982064594ba6 101 SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 10);
shimizuta 35:b4e1b8f25cd7 102 break;
shimizuta 42:982064594ba6 103 case LRFPOSTURE: //LRF用に変数はグローバルにある
shimizuta 35:b4e1b8f25cd7 104 for (int i = 0; i < 4; i++)
shimizuta 35:b4e1b8f25cd7 105 SetOneLegTriangleParam(walk, i, offset_x_m[i], offset_y_m[i],
shimizuta 35:b4e1b8f25cd7 106 stride_m[i], height_m[i], buffer_height_m,
shimizuta 35:b4e1b8f25cd7 107 stridetime_s, toptime_s, buffer_time_s);
shimizuta 35:b4e1b8f25cd7 108 walk.SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 35:b4e1b8f25cd7 109 break;
shimizuta 42:982064594ba6 110 case FRONTLEG_ON_SANDDUNE: //前足を段差にかける
shimizuta 42:982064594ba6 111 {
shimizuta 42:982064594ba6 112 float d_x_m = 0.1;
shimizuta 42:982064594ba6 113 float start_y_m[4] = {0.41, 0.41, 0.41, 0.41};
shimizuta 42:982064594ba6 114 float goal_y_m[4] = {0.41, 0.29, 0.41, 0.29};
shimizuta 42:982064594ba6 115 float overcome_height_m[] = {0.1, 0.2, 0.1, 0.2};
shimizuta 42:982064594ba6 116 float gravity_dist[] = {0.05, 0, 0.05, -0.05};
shimizuta 35:b4e1b8f25cd7 117 OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg);
shimizuta 35:b4e1b8f25cd7 118 walk.Copy(overcome.walk);
shimizuta 42:982064594ba6 119 break;
shimizuta 39:87dcdff27797 120 }
shimizuta 42:982064594ba6 121 case BACKLEG_ON_SANDDUNE: //後ろ脚を乗せる
shimizuta 42:982064594ba6 122 {
shimizuta 42:982064594ba6 123 float d_x_m = 0.1;
shimizuta 42:982064594ba6 124 float start_x_m[4] = {0, -0.08, 0, -0.08};
shimizuta 42:982064594ba6 125 float start_y_m[4] = {0.41, 0.41, 0.41, 0.41};
shimizuta 42:982064594ba6 126 float goal_y_m[4] = {0.29, 0.41, 0.29, 0.41};
shimizuta 42:982064594ba6 127 float overcome_height_m[] = {0.2, 0.1, 0.2, 0.1};
shimizuta 42:982064594ba6 128 float gravity_dist[] = {0.15, 0, 0.05, -0.05};
shimizuta 42:982064594ba6 129 OverCome overcome(start_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg);
shimizuta 42:982064594ba6 130 walk.Copy(overcome.walk);
shimizuta 42:982064594ba6 131 break;
shimizuta 42:982064594ba6 132 }
shimizuta 42:982064594ba6 133 case OVERCOME: //前足が乗った状態で進む
shimizuta 42:982064594ba6 134 {
shimizuta 42:982064594ba6 135 float offset_x_m[4] = {-0.15, 0.15, -0.15, 0.15},
shimizuta 42:982064594ba6 136 offset_y_m[4] = {0.35, 0.35, 0.35, 0.35};
shimizuta 42:982064594ba6 137 float stride_m[4] = {0.2, 0.2, 0.2, 0.2},
shimizuta 42:982064594ba6 138 height_m[4] = {0.1, 0.1, 0.1, 0.1}, buffer_height_m = 0.05,
shimizuta 42:982064594ba6 139 stridetime_s = 1, toptime_s = 0.2, buffer_time_s = 0.2;
shimizuta 39:87dcdff27797 140 for (int i = 0; i < 4; i++)
shimizuta 39:87dcdff27797 141 SetOneLegFourPointParam(walk, i, offset_x_m[i], offset_y_m[i],
shimizuta 39:87dcdff27797 142 stride_m[i], height_m[i], buffer_height_m,
shimizuta 39:87dcdff27797 143 stridetime_s, toptime_s, buffer_time_s);
shimizuta 39:87dcdff27797 144 walk.SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 35:b4e1b8f25cd7 145 break;
shimizuta 35:b4e1b8f25cd7 146 }
shimizuta 42:982064594ba6 147 case OVERCOME2: //後ろ脚が乗った状態で進む
shimizuta 42:982064594ba6 148 {
shimizuta 42:982064594ba6 149 float offset_x_m[4] = {},
shimizuta 42:982064594ba6 150 offset_y_m[4] = {0.35, 0.35, 0.35, 0.35};
shimizuta 42:982064594ba6 151 float stride_m[4] = {0.2, 0.2, 0.2, 0.2},
shimizuta 42:982064594ba6 152 height_m[4] = {0.1, 0.1, 0.1, 0.1}, buffer_height_m = 0.05,
shimizuta 42:982064594ba6 153 stridetime_s = 1, toptime_s = 0.2, buffer_time_s = 0.2;
shimizuta 42:982064594ba6 154 for (int i = 0; i < 4; i++)
shimizuta 42:982064594ba6 155 SetOneLegFourPointParam(walk, i, offset_x_m[i], offset_y_m[i],
shimizuta 42:982064594ba6 156 stride_m[i], height_m[i], buffer_height_m,
shimizuta 42:982064594ba6 157 stridetime_s, toptime_s, buffer_time_s);
shimizuta 42:982064594ba6 158 walk.SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 42:982064594ba6 159 break;
shimizuta 42:982064594ba6 160 }
shimizuta 42:982064594ba6 161 default:
shimizuta 42:982064594ba6 162 printf("error: there is no WalkWay\r\n");
shimizuta 42:982064594ba6 163 return 1;
shimizuta 42:982064594ba6 164 }
shimizuta 42:982064594ba6 165
shimizuta 35:b4e1b8f25cd7 166 return walk.CheckOrbit();
yuto17320508 18:0033ef1814ba 167 }
shimizuta 35:b4e1b8f25cd7 168
shimizuta 9:905f93247688 169 int main()
yuto17320508 5:556d5a5e9d24 170 {
shimizuta 29:7d8b8011a88d 171 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 172 if (FileOpen()) //csv fileに書き込み
shimizuta 27:79b4b932a6dd 173 return 1; //異常終了したら強制終了
shimizuta 29:7d8b8011a88d 174 #endif
shimizuta 39:87dcdff27797 175 OneLeg leg[4]; //各足の位置
shimizuta 35:b4e1b8f25cd7 176 for (int i = 0; i < 4; i++)
shimizuta 35:b4e1b8f25cd7 177 leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2);
shimizuta 39:87dcdff27797 178 Walk walk(leg); //歩行法はここに入れていく
shimizuta 35:b4e1b8f25cd7 179 Walk::calctime_s_ = 0.03;
shimizuta 42:982064594ba6 180 for (int i = 0; i < CHECK; i++)
shimizuta 42:982064594ba6 181 {
shimizuta 42:982064594ba6 182 if (SetWalk(walk, (WalkWay)i) == 1)
shimizuta 42:982064594ba6 183 {
shimizuta 42:982064594ba6 184 printf("error: move %d\r\n", i);
shimizuta 42:982064594ba6 185 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 42:982064594ba6 186 }
shimizuta 42:982064594ba6 187 }
shimizuta 35:b4e1b8f25cd7 188 printf("Stand up?\r\n");
shimizuta 35:b4e1b8f25cd7 189 WaitStdin('y'); // ボタンを押したら立つ
shimizuta 39:87dcdff27797 190 if (SetWalk(walk, STANDUP) == 1)
shimizuta 27:79b4b932a6dd 191 {
shimizuta 35:b4e1b8f25cd7 192 printf("error: stand move\r\n");
shimizuta 34:89d701e15cdf 193 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 194 }
shimizuta 39:87dcdff27797 195 MoveOneCycle(walk, leg);
shimizuta 29:7d8b8011a88d 196 printf("Move?\r\n");
shimizuta 27:79b4b932a6dd 197 WaitStdin('y'); // ボタンを押したらスタート
shimizuta 27:79b4b932a6dd 198 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 199 nh_mbed.getHardware()->setBaud(115200);
shimizuta 27:79b4b932a6dd 200 nh_mbed.initNode();
shimizuta 27:79b4b932a6dd 201 nh_mbed.subscribe(sub_vel);
shimizuta 42:982064594ba6 202 nh_mbed.subscribe(sub_state);
shimizuta 42:982064594ba6 203 nh_mbed.spinOnce(); //一度受信
shimizuta 39:87dcdff27797 204 while (1)
shimizuta 39:87dcdff27797 205 {
shimizuta 42:982064594ba6 206
shimizuta 39:87dcdff27797 207 SetWalk(walk, LRFPOSTURE);
shimizuta 39:87dcdff27797 208 MoveOneCycle(walk, leg);
shimizuta 27:79b4b932a6dd 209 nh_mbed.spinOnce();
shimizuta 42:982064594ba6 210 if (state_from_ros = SANDDUNE)
shimizuta 42:982064594ba6 211 {
shimizuta 42:982064594ba6 212 #endif
shimizuta 42:982064594ba6 213 //前足を段差にかける
shimizuta 42:982064594ba6 214 if (SetWalk(walk, FRONTLEG_ON_SANDDUNE) == 1)
shimizuta 42:982064594ba6 215 {
shimizuta 42:982064594ba6 216 printf("error: triangle\r\n");
shimizuta 42:982064594ba6 217 return 1; //強制終了.
shimizuta 42:982064594ba6 218 }
shimizuta 42:982064594ba6 219 for (int i = 0; i < 1; i++)
shimizuta 42:982064594ba6 220 MoveOneCycle(walk, leg);
shimizuta 42:982064594ba6 221 //前足が段差に乗った状態で進む
shimizuta 42:982064594ba6 222 if (SetWalk(walk, OVERCOME) == 1)
shimizuta 42:982064594ba6 223 {
shimizuta 42:982064594ba6 224 printf("error: triangle\r\n");
shimizuta 42:982064594ba6 225 return 1; //強制終了.
shimizuta 42:982064594ba6 226 }
shimizuta 42:982064594ba6 227 for (int i = 0; i < 5; i++)
shimizuta 42:982064594ba6 228 MoveOneCycle(walk, leg);
shimizuta 42:982064594ba6 229 //後ろ脚載せる
shimizuta 42:982064594ba6 230 if (SetWalk(walk, BACKLEG_ON_SANDDUNE) == 1)
shimizuta 42:982064594ba6 231 {
shimizuta 42:982064594ba6 232 printf("error: triangle\r\n");
shimizuta 42:982064594ba6 233 return 1; //強制終了.
shimizuta 42:982064594ba6 234 }
shimizuta 42:982064594ba6 235 for (int i = 0; i < 1; i++)
shimizuta 42:982064594ba6 236 MoveOneCycle(walk, leg);
shimizuta 42:982064594ba6 237 //後ろ脚乗った状態で進む
shimizuta 42:982064594ba6 238 if (SetWalk(walk, OVERCOME2) == 1)
shimizuta 42:982064594ba6 239 {
shimizuta 42:982064594ba6 240 printf("error: triangle\r\n");
shimizuta 42:982064594ba6 241 return 1; //強制終了.
shimizuta 42:982064594ba6 242 }
shimizuta 42:982064594ba6 243 for (int i = 0; i < 5; i++)
shimizuta 42:982064594ba6 244 MoveOneCycle(walk, leg);
shimizuta 42:982064594ba6 245 #ifdef USE_ROS
shimizuta 42:982064594ba6 246 }
yuto17320508 41:38d79b6513c0 247 }
shimizuta 42:982064594ba6 248 #endif
shimizuta 34:89d701e15cdf 249 printf("program end\r\n");
shimizuta 29:7d8b8011a88d 250 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 251 fclose(fp);
shimizuta 27:79b4b932a6dd 252 #endif
shimizuta 2:a92568bdeb5c 253 }
shimizuta 32:dc684a0b8448 254 //一サイクル分進む.return 1:異常終了
shimizuta 32:dc684a0b8448 255 int MoveOneCycle(Walk walkway, OneLeg leg[4])
yuto17320508 5:556d5a5e9d24 256 {
shimizuta 27:79b4b932a6dd 257 #ifndef VSCODE
shimizuta 9:905f93247688 258 timer.reset();
shimizuta 9:905f93247688 259 timer.start();
shimizuta 27:79b4b932a6dd 260 #endif
shimizuta 35:b4e1b8f25cd7 261 int count = walkway.orbit[0].GetOneWalkTime() / walkway.calctime_s_;
shimizuta 27:79b4b932a6dd 262 for (int i = 0; i < count; i++)
yuto17320508 8:21b932c4e6c5 263 {
shimizuta 27:79b4b932a6dd 264 #ifndef VSCODE
shimizuta 9:905f93247688 265 float time_s = timer.read();
shimizuta 27:79b4b932a6dd 266 #endif
shimizuta 29:7d8b8011a88d 267 //4本の足それぞれの足先サーボ角度更新
shimizuta 29:7d8b8011a88d 268 if (walkway.Cal4LegsPosi(leg) == 1)
shimizuta 32:dc684a0b8448 269 {
shimizuta 29:7d8b8011a88d 270 printf("error: time = %f\r\n", i * walkway.calctime_s_);
shimizuta 32:dc684a0b8448 271 return 1;
shimizuta 32:dc684a0b8448 272 }
shimizuta 19:1adc7302cfd9 273 #ifdef USE_CAN
shimizuta 27:79b4b932a6dd 274 SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信
shimizuta 19:1adc7302cfd9 275 #endif
shimizuta 9:905f93247688 276 //自身が動かす足のサーボを動かす
shimizuta 16:0069a56f11a3 277 MoveServo(leg[0], 0, 0);
shimizuta 11:e81425872740 278 MoveServo(leg[1], 1, 0);
shimizuta 27:79b4b932a6dd 279 #ifndef VSCODE
shimizuta 9:905f93247688 280 wait_ms(kServoSpan_ms);
shimizuta 27:79b4b932a6dd 281 #endif
shimizuta 16:0069a56f11a3 282 MoveServo(leg[0], 0, 1);
shimizuta 11:e81425872740 283 MoveServo(leg[1], 1, 1);
shimizuta 29:7d8b8011a88d 284 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 285 //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順
shimizuta 27:79b4b932a6dd 286 fprintf(fp, "%f", i * walkway.calctime_s_);
shimizuta 27:79b4b932a6dd 287 for (int i = 0; i < 4; i++)
shimizuta 27:79b4b932a6dd 288 fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m());
shimizuta 27:79b4b932a6dd 289 fprintf(fp, "\r\n");
shimizuta 29:7d8b8011a88d 290 #else
shimizuta 27:79b4b932a6dd 291 //計算周期がwalkway.calctime_s_になるようwait
shimizuta 27:79b4b932a6dd 292 float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s);
shimizuta 9:905f93247688 293 if (rest_time_s > 0)
shimizuta 9:905f93247688 294 wait(rest_time_s);
shimizuta 19:1adc7302cfd9 295 else
shimizuta 19:1adc7302cfd9 296 { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。
shimizuta 19:1adc7302cfd9 297 DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s);
shimizuta 14:d7cb429946f4 298 led[0] = 1;
shimizuta 14:d7cb429946f4 299 }
shimizuta 27:79b4b932a6dd 300 #endif
shimizuta 9:905f93247688 301 }
shimizuta 32:dc684a0b8448 302 return 0;
yuto17320508 5:556d5a5e9d24 303 }
shimizuta 14:d7cb429946f4 304 void MoveServo(OneLeg leg, int serial_num, int servo_id)
yuto17320508 6:43708adf2e5d 305 {
shimizuta 27:79b4b932a6dd 306 #ifndef VSCODE
shimizuta 11:e81425872740 307 float degree = leg.GetRad(servo_id) * kRadToDegree;
shimizuta 14:d7cb429946f4 308 //サーボの座標系に変更
shimizuta 14:d7cb429946f4 309 float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id];
shimizuta 27:79b4b932a6dd 310 // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree);
shimizuta 14:d7cb429946f4 311 servo[serial_num].set_degree(servo_id, servo_degree);
shimizuta 27:79b4b932a6dd 312 #endif
shimizuta 12:2ac37fe6c3bb 313 }
shimizuta 27:79b4b932a6dd 314 void WaitStdin(char startchar)
shimizuta 27:79b4b932a6dd 315 {
shimizuta 27:79b4b932a6dd 316 #ifndef USE_ROS
shimizuta 27:79b4b932a6dd 317 char str[255] = {};
shimizuta 27:79b4b932a6dd 318 do
shimizuta 27:79b4b932a6dd 319 {
shimizuta 27:79b4b932a6dd 320 printf("put '%c', then start\r\n", startchar);
shimizuta 27:79b4b932a6dd 321 scanf("%s", str);
shimizuta 27:79b4b932a6dd 322 } while (str[0] != startchar);
shimizuta 27:79b4b932a6dd 323 #endif
shimizuta 27:79b4b932a6dd 324 }
shimizuta 27:79b4b932a6dd 325 int FileOpen() //1:異常終了
shimizuta 27:79b4b932a6dd 326 {
shimizuta 27:79b4b932a6dd 327 if ((fp = fopen("data.csv", "w")) == NULL)
shimizuta 27:79b4b932a6dd 328 {
shimizuta 27:79b4b932a6dd 329 printf("error : FileSave()\r\n");
shimizuta 27:79b4b932a6dd 330 return 1;
shimizuta 27:79b4b932a6dd 331 }
shimizuta 27:79b4b932a6dd 332 fprintf(fp, "time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]\r\n");
shimizuta 27:79b4b932a6dd 333 return 0;
shimizuta 27:79b4b932a6dd 334 }
shimizuta 27:79b4b932a6dd 335 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 336 void callback(const geometry_msgs::Vector3 &cmd_vel)
shimizuta 27:79b4b932a6dd 337 {
shimizuta 42:982064594ba6 338 stride_m[LEFT_F] = cmd_vel.x;
shimizuta 42:982064594ba6 339 stride_m[LEFT_B] = cmd_vel.x;
shimizuta 42:982064594ba6 340 stride_m[RIGHT_F] = cmd_vel.y;
shimizuta 42:982064594ba6 341 stride_m[RIGHT_B] = cmd_vel.y;
shimizuta 42:982064594ba6 342 }
shimizuta 42:982064594ba6 343 void callback_state(const std_msgs::Int16 &cmd_vel)
shimizuta 42:982064594ba6 344 {
shimizuta 42:982064594ba6 345 state_from_ros = cmd_vel.data;
shimizuta 27:79b4b932a6dd 346 }
shimizuta 35:b4e1b8f25cd7 347 #endif