3/19 23:30
Dependencies: mbed move4wheel2 EC CruizCore_R1370P
can/can.cpp
- Committer:
- la00noix
- Date:
- 2019-02-26
- Revision:
- 2:7cba05e70367
- Parent:
- 1:3c11e07da92a
- Child:
- 3:8a0faa3b08c3
File content as of revision 2:7cba05e70367:
#include "mbed.h" #include "PathFollowing.h" #include "movement.h" #include "maxonsetting.h" #include "manual.h" #include "can.h" CAN can1(p30,p29,1000000); Ticker can_ticker; //can用ticker DigitalOut canread_led(LED1); //canread -> on DigitalOut cansend_led(LED2); //cansend -> on void can_readsend() { CANMessage msg; if(can1.read(msg)) { canread_led = 1; if(msg.id == 1){ //from main id1_value[0] = msg.data[0]; //decide mode(1~3) id1_value[1] = msg.data[1]; //angle of left joystick(0~359) id1_value[2] = msg.data[2]; id1_value[3] = msg.data[3]; //BOTTONR1 off/on(0 or 1) id1_value[4] = msg.data[4]; //state of right joystick(1~3) id1_value[5] = msg.data[5]; //left joystick neutral position(0 or 1) //debug_printf("[0]=%d [1]=%d [2]=%d [3]=%d [4]=%d [5]=%d\n\r",id1_value[0],id1_value[1],id1_value[2],id1_value[3],id1_value[4],id1_value[5]); } if(msg.id == 3){ usw_data1 = 0.1 * (short)((msg.data[0]<<8) | msg.data[1]); //debug_printf("usw_data1 = %f\n\r",usw_data1); } /*if(msg.id == 4){ usw_data2 = 0.1 * (short)((msg.data[0]<<8) | msg.data[1]); //debug_printf("usw_data2 = %f\n\r",usw_data2); }*/ /*if(msg.id == 5){ usw_data3 = 0.1 * (short)((msg.data[0]<<8) | msg.data[1]); //debug_printf("usw_data3 = %f\n\r",usw_data3); }*/ /*if(msg.id == 6){ usw_data4 = 0.1 * (short)((msg.data[0]<<8) | msg.data[1]); //debug_printf("usw_data4 = %f\n\r",usw_data4); }*/ }else{ canread_led = 0; } if(can1.write(CANMessage(7,ashi_data,4))) { //IDを7にして送信 cansend_led = 1; }else{ cansend_led = 0; } } void can_start(){ while(1){ CANMessage msg; debug_printf("wait\n\r"); wait(0.1); if(can1.read(msg)){ break; } } } void UserLoopSetting_can(){ can1.frequency(1000000); can_ticker.attach(&can_readsend,0.01); //遅かったら早める }