static void youbot_step(ubx_block_t *b) { struct youbot_info *inf=b->private_data; /* TODO set time out to zero? */ if(ec_receive_processdata(EC_TIMEOUTRET) == 0) { ERR("failed to receive processdata"); inf->pd_recv_err++; goto out_send; } if(inf->base.detected) base_proc_update(&inf->base); if(inf->arm1.detected) arm_proc_update(&inf->arm1); if(inf->arm2.detected) arm_proc_update(&inf->arm2); out_send: if (ec_send_processdata() <= 0){ ERR("failed to send processdata"); inf->pd_send_err++; } return; }
static int youbot_start(ubx_block_t *b) { DBG(" "); int ret=-1, i; struct youbot_info *inf=b->private_data; /* reset old commands */ if(inf->base.detected && base_prepare_start(&inf->base) != 0) goto out; if(inf->arm1.detected && arm_prepare_start(&inf->arm1) != 0) goto out; if(inf->arm2.detected && arm_prepare_start(&inf->arm2) != 0) goto out; /* requesting operational for all slaves */ ec_slave[0].state = EC_STATE_OPERATIONAL; ec_writestate(0); /* wait for all slaves to reach SAFE_OP state */ ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE); if(ec_slave[0].state != EC_STATE_OPERATIONAL) { ERR("not all slaves reached state operational:"); for (i=0; i<=ec_slavecount; i++) { if (ec_slave[i].state != EC_STATE_OPERATIONAL) { ERR("\tslave %d (%s) is in state=0x%x, ALstatuscode=0x%x", i, ec_slave[i].name, ec_slave[i].state, ec_slave[i].ALstatuscode); } } goto out; } /* get things rolling */ if (ec_send_processdata() <= 0) { inf->pd_send_err++; ERR("sending initial process data failed"); } /* cache port pointers */ assert(inf->base.p_control_mode = ubx_port_get(b, "base_control_mode")); assert(inf->base.p_cmd_twist = ubx_port_get(b, "base_cmd_twist")); assert(inf->base.p_cmd_vel = ubx_port_get(b, "base_cmd_vel")); assert(inf->base.p_cmd_cur = ubx_port_get(b, "base_cmd_cur")); assert(inf->base.p_msr_odom = ubx_port_get(b, "base_msr_odom")); assert(inf->base.p_msr_twist = ubx_port_get(b, "base_msr_twist")); assert(inf->base.p_base_motorinfo = ubx_port_get(b, "base_motorinfo")); assert(inf->arm1.p_control_mode = ubx_port_get(b, "arm1_control_mode")); assert(inf->arm1.p_calibrate_cmd = ubx_port_get(b, "arm1_calibrate_cmd")); assert(inf->arm1.p_cmd_pos = ubx_port_get(b, "arm1_cmd_pos")); assert(inf->arm1.p_cmd_vel = ubx_port_get(b, "arm1_cmd_vel")); assert(inf->arm1.p_cmd_cur = ubx_port_get(b, "arm1_cmd_cur")); assert(inf->arm1.p_cmd_eff = ubx_port_get(b, "arm1_cmd_eff")); assert(inf->arm1.p_arm_state = ubx_port_get(b, "arm1_state")); assert(inf->arm1.p_arm_motorinfo = ubx_port_get(b, "arm1_motorinfo")); assert(inf->arm1.p_gripper = ubx_port_get(b, "arm1_gripper")); ret=0; out: return ret; }
/* most basic RT thread for process data, just does IO transfer */ void CALLBACK RTthread(UINT uTimerID, UINT uMsg, DWORD_PTR dwUser, DWORD_PTR dw1, DWORD_PTR dw2) { IOmap[0]++; ec_send_processdata(); wkc = ec_receive_processdata(EC_TIMEOUTRET); rtcnt++; /* do RT control stuff here */ }
static void CALLBACK ioTransferThread(UINT /*uTimerID*/, UINT /*uMsg*/, DWORD_PTR /*dwUser*/, DWORD_PTR /*dw1*/, DWORD_PTR /*dw2*/) { iomap[0]++; auto wkc1 = ec_send_processdata(); //auto wkc2 = ec_receive_processdata(EC_TIMEOUTRET); auto wkc2 = ec_receive_processdata(EC_TIMEOUTSAFE); if (wkc1 <= 0 || wkc2 <= 0) globalErrorFlag.store(GLOBAL_ERROR); }
/* RT EtherCAT thread */ OSAL_THREAD_FUNC_RT ecatthread(void *ptr) { struct timespec ts, tleft; int ht; int64 cycletime; clock_gettime(CLOCK_MONOTONIC, &ts); ht = (ts.tv_nsec / 1000000) + 1; /* round to nearest ms */ ts.tv_nsec = ht * 1000000; cycletime = *(int*)ptr * 1000; /* cycletime in ns */ toff = 0; dorun = 0; ec_send_processdata(); while(1) { /* calculate next cycle start */ add_timespec(&ts, cycletime + toff); /* wait to cycle start */ clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &ts, &tleft); if (dorun>0) { wkc = ec_receive_processdata(EC_TIMEOUTRET); dorun++; /* if we have some digital output, cycle */ if( digout ) *digout = (uint8) ((dorun / 16) & 0xff); if (ec_slave[0].hasdc) { /* calulate toff to get linux time and DC synced */ ec_sync(ec_DCtime, cycletime, &toff); } ec_send_processdata(); } } }
void simpletest(char *ifname) { int i, j, oloop, iloop, wkc_count, chk; needlf = FALSE; inOP = FALSE; printf("Starting simple test\n"); /* initialise SOEM, bind socket to ifname */ if (ec_init(ifname)) { printf("ec_init on %s succeeded.\n",ifname); /* find and auto-config slaves */ if ( ec_config_init(FALSE) > 0 ) { printf("%d slaves found and configured.\n",ec_slavecount); ec_config_map(&IOmap); ec_configdc(); printf("Slaves mapped, state to SAFE_OP.\n"); /* wait for all slaves to reach SAFE_OP state */ ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 4); oloop = ec_slave[0].Obytes; if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1; if (oloop > 8) oloop = 8; iloop = ec_slave[0].Ibytes; if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1; if (iloop > 8) iloop = 8; printf("segments : %d : %d %d %d %d\n",ec_group[0].nsegments ,ec_group[0].IOsegment[0],ec_group[0].IOsegment[1],ec_group[0].IOsegment[2],ec_group[0].IOsegment[3]); printf("Request operational state for all slaves\n"); expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC; printf("Calculated workcounter %d\n", expectedWKC); ec_slave[0].state = EC_STATE_OPERATIONAL; /* send one valid process data to make outputs in slaves happy*/ ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); /* request OP state for all slaves */ ec_writestate(0); chk = 40; /* wait for all slaves to reach OP state */ do { ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); ec_statecheck(0, EC_STATE_OPERATIONAL, 50000); } while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL)); if (ec_slave[0].state == EC_STATE_OPERATIONAL ) { printf("Operational state reached for all slaves.\n"); wkc_count = 0; inOP = TRUE; /* cyclic loop */ for(i = 1; i <= 10000; i++) { ec_send_processdata(); wkc = ec_receive_processdata(EC_TIMEOUTRET); if(wkc >= expectedWKC) { printf("Processdata cycle %4d, WKC %d , O:", i, wkc); for(j = 0 ; j < oloop; j++) { printf(" %2.2x", *(ec_slave[0].outputs + j)); } printf(" I:"); for(j = 0 ; j < iloop; j++) { printf(" %2.2x", *(ec_slave[0].inputs + j)); } printf(" T:%lld\r",ec_DCtime); needlf = TRUE; } usleep(5000); } inOP = FALSE; } else { printf("Not all slaves reached operational state.\n"); ec_readstate(); for(i = 1; i<=ec_slavecount ; i++) { if(ec_slave[i].state != EC_STATE_OPERATIONAL) { printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n", i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode)); } } } printf("\nRequest init state for all slaves\n"); ec_slave[0].state = EC_STATE_INIT; /* request INIT state for all slaves */ ec_writestate(0); } else { printf("No slaves found!\n"); } printf("End simple test, close socket\n"); /* stop SOEM, close socket */ ec_close(); } else { printf("No socket connection on %s\nExcecute as root\n",ifname); } }
static int youbot_init(ubx_block_t *b) { int ret=-1, i, cur_slave; unsigned int len; char* interface; uint32_t *conf_nr_arms; struct youbot_info *inf; interface = (char *) ubx_config_get_data_ptr(b, "ethernet_if", &len); conf_nr_arms = (uint32_t *) ubx_config_get_data_ptr(b, "nr_arms", &len); if(strncmp(interface, "", len)==0) { ERR("config ethernet_if unset"); goto out; } /* allocate driver data */ if((inf=calloc(1, sizeof(struct youbot_info)))==NULL) { ERR("failed to alloc youbot_info"); goto out; } b->private_data=inf; if(ec_init(interface) <= 0) { ERR("ec_init failed (IF=%s), sufficient rights, correct interface?", interface); goto out_free; } if(ec_config(TRUE, &inf->io_map) <= 0) { ERR("ec_config failed (IF=%s)", interface); goto out_free; } else { DBG("detected %d slaves", ec_slavecount); } /* Let's see what we have... * check for base, base is mandatory for a youbot */ if(ec_slavecount >= YOUBOT_NR_OF_BASE_SLAVES && validate_base_slaves(1) == 0) { DBG("detected youbot base"); inf->base.detected=1; for(i=0, cur_slave=2; i<YOUBOT_NR_OF_WHEELS; i++, cur_slave++) inf->base.wheel_inf[i].slave_idx=cur_slave; } else { ERR("no base detected"); goto out_free; } /* check for first arm */ if(ec_slavecount >= (YOUBOT_NR_OF_BASE_SLAVES + YOUBOT_NR_OF_ARM_SLAVES) && validate_arm_slaves(1+YOUBOT_NR_OF_BASE_SLAVES)==0) { DBG("detected youbot arm #1 (first slave=%d)", cur_slave); inf->arm1.detected=1; *conf_nr_arms=1; cur_slave++; /* skip the power board */ for(i=0; i<YOUBOT_NR_OF_JOINTS; i++, cur_slave++) inf->arm1.jnt_inf[i].slave_idx=cur_slave; } /* check for second arm */ if(ec_slavecount >= (YOUBOT_NR_OF_BASE_SLAVES + (2 * YOUBOT_NR_OF_ARM_SLAVES)) && validate_arm_slaves(1+YOUBOT_NR_OF_BASE_SLAVES+YOUBOT_NR_OF_ARM_SLAVES)==0) { DBG("detected youbot arm #2 (first slave=%d)", cur_slave); inf->arm2.detected=1; *conf_nr_arms=2; cur_slave++; /* skip the power board */ for(i=0; i<YOUBOT_NR_OF_JOINTS; i++, cur_slave++) inf->arm2.jnt_inf[i].slave_idx=cur_slave; } /* wait for all slaves to reach SAFE_OP state */ ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE); if(ec_slave[0].state != EC_STATE_SAFE_OP) { ERR("not all slaves reached state safe_operational:"); for (i=0; i<=ec_slavecount; i++) { if (ec_slave[i].state != EC_STATE_SAFE_OP) { ERR("\tslave %d (%s) is in state=0x%x, ALstatuscode=0x%x", i, ec_slave[i].name, ec_slave[i].state, ec_slave[i].ALstatuscode); } } goto out_free; } /* send and receive bogus process data to get things going */ if(ec_send_processdata() <= 0) { ERR("failed to send bootstrap process data"); goto out_free; } if(ec_receive_processdata(EC_TIMEOUTRET) == 0) { ERR("failed to receive bootstrap process data"); goto out_free; } if(inf->base.detected) base_config_params(&inf->base); if(inf->arm1.detected) arm_config_params(&inf->arm1); if(inf->arm2.detected) arm_config_params(&inf->arm2); #if 0 int tmp /* find firmware version */ if(send_mbx(0, FIRMWARE_VERSION, 1, 0, 0, &tmp)) { ERR("Failed to read firmware version"); goto out; } else DBG("youbot firmware version %d", tmp); #endif ret=0; goto out; out_free: free(b->private_data); out: return ret; }
void simpletest(char *ifname) { int i, j, oloop, iloop, wkc_count, chk, slc; UINT mmResult; needlf = FALSE; inOP = FALSE; printf("Starting simple test\n"); /* initialise SOEM, bind socket to ifname */ if (ec_init(ifname)) { printf("ec_init on %s succeeded.\n",ifname); /* find and auto-config slaves */ if ( ec_config_init(FALSE) > 0 ) { printf("%d slaves found and configured.\n",ec_slavecount); if((ec_slavecount > 1)) { for(slc = 1; slc <= ec_slavecount; slc++) { // beckhoff EL7031, using ec_slave[].name is not very reliable if((ec_slave[slc].eep_man == 0x00000002) && (ec_slave[slc].eep_id == 0x1b773052)) { printf("Found %s at position %d\n", ec_slave[slc].name, slc); // link slave specific setup to preop->safeop hook ec_slave[slc].PO2SOconfig = &EL7031setup; } // Copley Controls EAP, using ec_slave[].name is not very reliable if((ec_slave[slc].eep_man == 0x000000ab) && (ec_slave[slc].eep_id == 0x00000380)) { printf("Found %s at position %d\n", ec_slave[slc].name, slc); // link slave specific setup to preop->safeop hook ec_slave[slc].PO2SOconfig = &AEPsetup; } } } ec_config_map(&IOmap); ec_configdc(); printf("Slaves mapped, state to SAFE_OP.\n"); /* wait for all slaves to reach SAFE_OP state */ ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 4); oloop = ec_slave[0].Obytes; if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1; if (oloop > 8) oloop = 8; iloop = ec_slave[0].Ibytes; if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1; if (iloop > 8) iloop = 8; printf("segments : %d : %d %d %d %d\n",ec_group[0].nsegments ,ec_group[0].IOsegment[0],ec_group[0].IOsegment[1],ec_group[0].IOsegment[2],ec_group[0].IOsegment[3]); printf("Request operational state for all slaves\n"); expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC; printf("Calculated workcounter %d\n", expectedWKC); ec_slave[0].state = EC_STATE_OPERATIONAL; /* send one valid process data to make outputs in slaves happy*/ ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); /* start RT thread as periodic MM timer */ mmResult = timeSetEvent(1, 0, RTthread, 0, TIME_PERIODIC); /* request OP state for all slaves */ ec_writestate(0); chk = 40; /* wait for all slaves to reach OP state */ do { ec_statecheck(0, EC_STATE_OPERATIONAL, 50000); } while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL)); if (ec_slave[0].state == EC_STATE_OPERATIONAL ) { printf("Operational state reached for all slaves.\n"); wkc_count = 0; inOP = TRUE; /* cyclic loop, reads data from RT thread */ for(i = 1; i <= 500; i++) { if(wkc >= expectedWKC) { printf("Processdata cycle %4d, WKC %d , O:", rtcnt, wkc); for(j = 0 ; j < oloop; j++) { printf(" %2.2x", *(ec_slave[0].outputs + j)); } printf(" I:"); for(j = 0 ; j < iloop; j++) { printf(" %2.2x", *(ec_slave[0].inputs + j)); } printf(" T:%lld\r",ec_DCtime); needlf = TRUE; } osal_usleep(50000); } inOP = FALSE; } else { printf("Not all slaves reached operational state.\n"); ec_readstate(); for(i = 1; i<=ec_slavecount ; i++) { if(ec_slave[i].state != EC_STATE_OPERATIONAL) { printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n", i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode)); } } } /* stop RT thread */ timeKillEvent(mmResult); printf("\nRequest init state for all slaves\n"); ec_slave[0].state = EC_STATE_INIT; /* request INIT state for all slaves */ ec_writestate(0); } else { printf("No slaves found!\n"); } printf("End simple test, close socket\n"); /* stop SOEM, close socket */ ec_close(); } else { printf("No socket connection on %s\nExcecute as root\n",ifname); } }
/* RT EtherCAT thread */ void ecatthread( void *ptr ) { struct timespec ts; struct timeval tp; int rc; int ht; int i; int pcounter = 0; int64 cycletime; rc = pthread_mutex_lock(&mutex); rc = gettimeofday(&tp, NULL); /* Convert from timeval to timespec */ ts.tv_sec = tp.tv_sec; ht = (tp.tv_usec / 1000) + 1; /* round to nearest ms */ ts.tv_nsec = ht * 1000000; cycletime = *(int*)ptr * 1000; /* cycletime in ns */ toff = 0; dorun = 0; while(1) { /* calculate next cycle start */ add_timespec(&ts, cycletime + toff); /* wait to cycle start */ rc = pthread_cond_timedwait(&cond, &mutex, &ts); if (dorun>0) { rc = gettimeofday(&tp, NULL); ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); cyclecount++; if((in_EBOX->counter != pcounter) && (streampos < (MAXSTREAM - 1))) { // check if we have timing problems in master // if so, overwrite stream data so it shows up clearly in plots. if(in_EBOX->counter > (pcounter + 1)) for(i = 0 ; i < 50 ; i++) { stream1[streampos] = 20000; stream2[streampos++] = -20000; } else for(i = 0 ; i < 50 ; i++) { stream1[streampos] = in_EBOX->stream[i * 2]; stream2[streampos++] = in_EBOX->stream[(i * 2) + 1]; } pcounter = in_EBOX->counter; } /* calulate toff to get linux time and DC synced */ ec_sync(ec_DCtime, cycletime, &toff); } } }
void eboxtest(char *ifname) { int cnt, i; printf("Starting E/BOX test\n"); /* initialise SOEM, bind socket to ifname */ if (ec_init(ifname)) { printf("ec_init on %s succeeded.\n",ifname); /* find and auto-config slaves */ if ( ec_config_init(FALSE) > 0 ) { printf("%d slaves found and configured.\n",ec_slavecount); // check if first slave is an E/BOX if (( ec_slavecount >= 1 ) && (strcmp(ec_slave[1].name,"E/BOX") == 0)) { // reprogram PDO mapping to set slave in stream mode // this can only be done in pre-OP state os=sizeof(ob2); ob2 = 0x1601; ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM); os=sizeof(ob2); ob2 = 0x1a01; ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM); } ec_config_map(&IOmap); ec_configdc(); /* wait for all slaves to reach SAFE_OP state */ ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE); /* configure DC options for every DC capable slave found in the list */ printf("DC capable : %d\n",ec_configdc()); /* check configuration */ if (( ec_slavecount >= 1 ) && (strcmp(ec_slave[1].name,"E/BOX") == 0) ) { printf("E/BOX found.\n"); /* connect struct pointers to slave I/O pointers */ in_EBOX = (in_EBOX_streamt*) ec_slave[1].inputs; out_EBOX = (out_EBOX_streamt*) ec_slave[1].outputs; /* read indevidual slave state and store in ec_slave[] */ ec_readstate(); for(cnt = 1; cnt <= ec_slavecount ; cnt++) { printf("Slave:%d Name:%s Output size:%3dbits Input size:%3dbits State:%2d delay:%d.%d\n", cnt, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits, ec_slave[cnt].state, (int)ec_slave[cnt].pdelay, ec_slave[cnt].hasdc); } printf("Request operational state for all slaves\n"); /* send one processdata cycle to init SM in slaves */ ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); ec_slave[0].state = EC_STATE_OPERATIONAL; /* request OP state for all slaves */ ec_writestate(0); /* wait for all slaves to reach OP state */ ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE); if (ec_slave[0].state == EC_STATE_OPERATIONAL ) { printf("Operational state reached for all slaves.\n"); ain[0] = 0; ain[1] = 0; ainc = 0; dorun = 1; usleep(100000); // wait for linux to sync on DC ec_dcsync0(1, TRUE, SYNC0TIME, 0); // SYNC0 on slave 1 /* acyclic loop 20ms */ for(i = 1; i <= 200; i++) { /* read DC difference register for slave 2 */ // ec_FPRD(ec_slave[1].configadr, ECT_REG_DCSYSDIFF, sizeof(DCdiff), &DCdiff, EC_TIMEOUTRET); // if(DCdiff<0) { DCdiff = - (int32)((uint32)DCdiff & 0x7ffffff); } printf("PD cycle %5d DCtime %12lld Cnt:%3d Data: %6d %6d %6d %6d %6d %6d %6d %6d \n", cyclecount, ec_DCtime, in_EBOX->counter, in_EBOX->stream[0], in_EBOX->stream[1], in_EBOX->stream[2], in_EBOX->stream[3], in_EBOX->stream[4], in_EBOX->stream[5], in_EBOX->stream[98], in_EBOX->stream[99]); usleep(20000); } dorun = 0; // printf("\nCnt %d : Ain0 = %f Ain2 = %f\n", ainc, ain[0] / ainc, ain[1] / ainc); } else { printf("Not all slaves reached operational state.\n"); } } else { printf("E/BOX not found in slave configuration.\n"); } ec_dcsync0(1, FALSE, 8000, 0); // SYNC0 off printf("Request safe operational state for all slaves\n"); ec_slave[0].state = EC_STATE_SAFE_OP; /* request SAFE_OP state for all slaves */ ec_writestate(0); /* wait for all slaves to reach state */ ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE); ec_slave[0].state = EC_STATE_PRE_OP; /* request SAFE_OP state for all slaves */ ec_writestate(0); /* wait for all slaves to reach state */ ec_statecheck(0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE); if (( ec_slavecount >= 1 ) && (strcmp(ec_slave[1].name,"E/BOX") == 0)) { // restore PDO to standard mode // this can only be done is pre-op state os=sizeof(ob2); ob2 = 0x1600; ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM); os=sizeof(ob2); ob2 = 0x1a00; ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM); } printf("Streampos %d\n", streampos); output_cvs("stream.txt", streampos); } else { printf("No slaves found!\n"); } printf("End E/BOX, close socket\n"); /* stop SOEM, close socket */ ec_close(); } else { printf("No socket connection on %s\nExcecute as root\n",ifname); } }
///sends and receives ethercat messages and mailbox messages to and from the motor controllers ///this method is executed in a separate thread void EthercatMaster::updateSensorActorValues() { // Bouml preserved body begin 0003F771 long timeToWait = 0; ptime startTime = microsec_clock::local_time(); time_duration pastTime; int counter = 0; time_duration realperiode; time_duration timeSum = startTime - startTime; while (!stopThread) { pastTime = microsec_clock::local_time() - startTime; timeToWait = timeTillNextEthercatUpdate - pastTime.total_microseconds() - 100; if(timeToWait < 0 || timeToWait > timeTillNextEthercatUpdate){ // printf("Missed communication period of %d microseconds it have been %d microseconds \n",timeTillNextEthercatUpdate, (int)pastTime.total_microseconds()+ 100); }else{ boost::this_thread::sleep(boost::posix_time::microseconds(timeToWait)); } // realperiode = microsec_clock::local_time() - startTime; startTime = microsec_clock::local_time(); /* counter++; timeSum = timeSum + realperiode; if(counter == 100){ double dtotaltime = (double)timeSum.total_microseconds()/counter; printf("TotalTime %7.0lf us\n", dtotaltime); counter = 0; timeSum = startTime - startTime; } */ //check if for joint limits // this->checkJointLimits(); //TODO test joint limit check //send and receive data from ethercat if (ec_send_processdata() == 0) { LOG(warning) << "Sending process data failed"; } if (ec_receive_processdata(this->ethercatTimeout) == 0) { if(communicationErrors == 0){ LOG(warning) << "Receiving data failed"; } communicationErrors++; }else{ communicationErrors = 0; } if(communicationErrors > maxCommunicationErrors){ LOG(error) << "Lost EtherCAT connection"; this->closeEthercat(); stopThread = true; break; } if (ec_iserror()) LOG(warning) << "there is an error in the soem driver"; if (newDataFlagOne == false) { { boost::mutex::scoped_lock dataMutex1(mutexDataOne); for (unsigned int i = 0; i < firstBufferVector.size(); i++) { //fill first output buffer (send data) if (newOutputDataFlagOne[i]) { *(ethercatOutputBufferVector[i]) = (firstBufferVector[i]).stctOutput; } //fill first input buffer (receive data) (firstBufferVector[i]).stctInput = *(ethercatInputBufferVector[i]); // this->parseYouBotErrorFlags(secondBufferVector[i]); //send mailbox messages from first buffer if (newMailboxDataFlagOne[i]) { sendMailboxMessage(firstMailboxBufferVector[i]); newMailboxDataFlagOne[i] = false; pendingMailboxMsgsReply[i] = true; } //receive mailbox messages to first buffer if(pendingMailboxMsgsReply[i]){ if (receiveMailboxMessage(firstMailboxBufferVector[i])) { newMailboxInputDataFlagOne[i] = true; pendingMailboxMsgsReply[i] = false; } } } } newDataFlagOne = true; newDataFlagTwo = false; } else if (newDataFlagTwo == false) { { boost::mutex::scoped_lock dataMutex2(mutexDataTwo); for (unsigned int i = 0; i < secondBufferVector.size(); i++) { //fill second output buffer (send data) if (newOutputDataFlagTwo[i]) { *(ethercatOutputBufferVector[i]) = (secondBufferVector[i]).stctOutput; } //fill second input buffer (receive data) (secondBufferVector[i]).stctInput = *(ethercatInputBufferVector[i]); // this->parseYouBotErrorFlags(secondBufferVector[i]); //send mailbox messages from second buffer if (newMailboxDataFlagTwo[i]) { sendMailboxMessage(secondMailboxBufferVector[i]); newMailboxDataFlagTwo[i] = false; pendingMailboxMsgsReply[i] = true; } //receive mailbox messages to second buffer if(pendingMailboxMsgsReply[i]){ if (receiveMailboxMessage(secondMailboxBufferVector[i])) { newMailboxInputDataFlagTwo[i] = true; pendingMailboxMsgsReply[i] = false; } } } } newDataFlagTwo = true; newDataFlagOne = false; } // if(ethercatInputBufferVector[3]->actualCurrent >= 900 ){ // printf("joint 3 encoder: %d current %d \n", ethercatInputBufferVector[3]->actualPosition, ethercatInputBufferVector[3]->actualCurrent); // } // int cnt = 7; // printf("activeports:%i DCrtA:%i DCrtB:%d DCrtC:%d DCrtD:%d\n", (int)ec_slave[cnt].activeports, ec_slave[cnt].DCrtA, ec_slave[cnt].DCrtB, ec_slave[cnt].DCrtC, ec_slave[cnt].DCrtD); // printf("next DC slave:%i previous DC slave:%i DC cyle time in ns:%d DC shift:%d DC sync activation:%d\n", ec_slave[cnt].DCnext, ec_slave[cnt].DCprevious, ec_slave[cnt].DCcycle, ec_slave[cnt].DCshift, ec_slave[cnt].DCactive); // for (unsigned int i = 0; i < motorProtections.size(); i++) { // if (motorProtections[i].createSafeMotorCommands(stopMotorCommand)) { // *(ethercatOutputBufferVector[i]) = stopMotorCommand.stctOutput; // } // } } // Bouml preserved body end 0003F771 }
///establishes the ethercat connection void EthercatMaster::initializeEthercat() { // Bouml preserved body begin 000410F1 /* initialise SOEM, bind socket to ifname */ if (ec_init(ethernetDevice.c_str())) { LOG(info) << "Initializing EtherCAT on " << ethernetDevice; /* find and auto-config slaves */ if (ec_config(TRUE, &IOmap_) > 0) { LOG(trace) << ec_slavecount << " slaves found and configured."; /* wait for all slaves to reach Pre OP state */ /*ec_statecheck(0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE); if (ec_slave[0].state != EC_STATE_PRE_OP ){ printf("Not all slaves reached pre operational state.\n"); ec_readstate(); //If not all slaves operational find out which one for(int i = 1; i<=ec_slavecount ; i++){ if(ec_slave[i].state != EC_STATE_PRE_OP){ printf("Slave %d State=%2x StatusCode=%4x : %s\n", i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode)); } } } */ /* distributed clock is not working //Configure distributed clock if(!ec_configdc()){ LOG(warning) << "no distributed clock is available"; }else{ uint32 CyclTime = 4000000; uint32 CyclShift = 0; for (int i = 1; i <= ec_slavecount; i++) { ec_dcsync0(i, true, CyclTime, CyclShift); } } */ /* wait for all slaves to reach SAFE_OP state */ ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE); if (ec_slave[0].state != EC_STATE_SAFE_OP) { LOG(warning) << "Not all slaves reached safe operational state."; ec_readstate(); //If not all slaves operational find out which one for (int i = 1; i <= ec_slavecount; i++) { if (ec_slave[i].state != EC_STATE_SAFE_OP) { LOG(info) << "Slave " << i << " State=" << ec_slave[i].state << " StatusCode=" << ec_slave[i].ALstatuscode << " : " << ec_ALstatuscode2string(ec_slave[i].ALstatuscode); } } } //Read the state of all slaves //ec_readstate(); LOG(trace) << "Request operational state for all slaves"; ec_slave[0].state = EC_STATE_OPERATIONAL; // request OP state for all slaves /* send one valid process data to make outputs in slaves happy*/ ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); /* request OP state for all slaves */ ec_writestate(0); // wait for all slaves to reach OP state ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE); if (ec_slave[0].state == EC_STATE_OPERATIONAL) { LOG(trace) << "Operational state reached for all slaves."; } else { throw std::runtime_error("Not all slaves reached operational state."); } } else { throw std::runtime_error("No slaves found!"); } } else { throw std::runtime_error("No socket connection on " + ethernetDevice + "\nExcecute as root"); } std::string baseJointControllerName = "TMCM-174"; std::string manipulatorJointControllerName = "TMCM-174"; std::string actualSlaveName; nrOfSlaves = 0; YouBotSlaveMsg emptySlaveMsg; quantity<si::current> maxContinuousCurrentBase = 3.54 * ampere; quantity<si::time> thermalTimeConstantWindingBase = 16.6 * second; quantity<si::time> thermalTimeConstantMotorBase = 212 * second; quantity<si::current> maxContinuousCurrentJoint13 = 2.36 * ampere; quantity<si::time> thermalTimeConstantWindingJoint13 = 16.6 * second; quantity<si::time> thermalTimeConstantMotorJoint13 = 212 * second; quantity<si::current> maxContinuousCurrentJoint4 = 1.07 * ampere; quantity<si::time> thermalTimeConstantWindingJoint4 = 13.2 * second; quantity<si::time> thermalTimeConstantMotorJoint4 = 186 * second; quantity<si::current> maxContinuousCurrentJoint5 = 0.49 * ampere; quantity<si::time> thermalTimeConstantWindingJoint5 = 8.1 * second; quantity<si::time> thermalTimeConstantMotorJoint5 = 108 * second; int manipulatorNo = 0; configfile->readInto(baseJointControllerName, "BaseJointControllerName"); configfile->readInto(manipulatorJointControllerName, "ManipulatorJointControllerName"); //reserve memory for all slave with a input/output buffer for (int cnt = 1; cnt <= ec_slavecount; cnt++) { // printf("Slave:%d Name:%s Output size:%3dbits Input size:%3dbits State:%2d delay:%d.%d\n", // cnt, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits, // ec_slave[cnt].state, (int) ec_slave[cnt].pdelay, ec_slave[cnt].hasdc); ethercatSlaveInfo.push_back(ec_slave[cnt]); actualSlaveName = ec_slave[cnt].name; if ((actualSlaveName == baseJointControllerName || actualSlaveName == manipulatorJointControllerName) && ec_slave[cnt].Obits > 0 && ec_slave[cnt].Ibits > 0) { nrOfSlaves++; // joints.push_back(YouBotJoint(nrOfSlaves)); firstBufferVector.push_back(emptySlaveMsg); secondBufferVector.push_back(emptySlaveMsg); ethercatOutputBufferVector.push_back((SlaveMessageOutput*) (ec_slave[cnt].outputs)); ethercatInputBufferVector.push_back((SlaveMessageInput*) (ec_slave[cnt].inputs)); YouBotSlaveMailboxMsg emptyMailboxSlaveMsg(cnt); firstMailboxBufferVector.push_back(emptyMailboxSlaveMsg); secondMailboxBufferVector.push_back(emptyMailboxSlaveMsg); newOutputDataFlagOne.push_back(false); newOutputDataFlagTwo.push_back(false); newMailboxDataFlagOne.push_back(false); newMailboxDataFlagTwo.push_back(false); newMailboxInputDataFlagOne.push_back(false); newMailboxInputDataFlagTwo.push_back(false); pendingMailboxMsgsReply.push_back(false); int i = 0; bool b = false; upperLimit.push_back(i); lowerLimit.push_back(i); limitActive.push_back(b); jointLimitReached.push_back(b); inverseMovementDirection.push_back(b); if (actualSlaveName == baseJointControllerName) { motorProtections.push_back(MotorProtection(maxContinuousCurrentBase, thermalTimeConstantWindingBase, thermalTimeConstantMotorBase)); } if (actualSlaveName == manipulatorJointControllerName) { manipulatorNo++; if (manipulatorNo >= 1 && manipulatorNo <= 3) { motorProtections.push_back(MotorProtection(maxContinuousCurrentJoint13, thermalTimeConstantWindingJoint13, thermalTimeConstantMotorJoint13)); } if (manipulatorNo == 4) { motorProtections.push_back(MotorProtection(maxContinuousCurrentJoint4, thermalTimeConstantWindingJoint4, thermalTimeConstantMotorJoint4)); } if (manipulatorNo == 5) { motorProtections.push_back(MotorProtection(maxContinuousCurrentJoint5, thermalTimeConstantWindingJoint5, thermalTimeConstantMotorJoint5)); manipulatorNo = 0; } } } } if (nrOfSlaves != motorProtections.size()) { throw std::runtime_error("Insufficient motor protections loaded"); } if (nrOfSlaves > 0) { LOG(info) << nrOfSlaves << " EtherCAT slaves found" ; } else { throw std::runtime_error("No EtherCAT slave could be found"); return; } stopThread = false; threads.create_thread(boost::bind(&EthercatMaster::updateSensorActorValues, this)); SLEEP_MILLISEC(10); //needed to start up thread and EtherCAT communication return; // Bouml preserved body end 000410F1 }
inline void ConnManager::cycleECat() { ec_send_processdata(); ec_receive_processdata(EC_TIMEOUT_US); }
bool Drive::open(const QString& adapterName) { qDebug() << "drive: open " << adapterName; bool ok = true; if (isOpened) { assert(false && "repeated call is not supported"); ok = false; } if (ok) { strcpy_s(adapterNameBuffer, adapterName.toStdString().c_str()); // TODO уязвимость // initialise SOEM, bind socket to adapterNameBuffer if (ec_init(adapterNameBuffer) <= 0) { qDebug() << "ошибка ec_init"; ok = false; } } // find and auto-config slaves if (ok) { isOpened = true; // TODO правильное ли место? const auto slaveCount = ec_config_init(0); if (slaveCount != 1) { qDebug() << "количество найденных устройств равно " << slaveCount; if (slaveCount == EC_OTHERFRAME) qDebug() << "Ошибка: unknown frame received"; else if (slaveCount == EC_NOFRAME) qDebug() << "Ошибка: no frame returned"; ok = false; } } if (ok) { // проверка, что подключен именно наш мотор auto slave = &ec_slave[1]; if (slave->eep_man != 599 || slave->eep_id != 41220) { qDebug() << "eep_man: " << slave->eep_man << ", slave->eep_id: " << slave->eep_id; ok = false; } ec_slave[1].PO2SOconfig = &myPdoSetup; } if (ok) { // Map all PDOs from slaves to iomap ec_config_map(&iomap); // wait for all slaves to reach SAFE_OP state ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 4); ec_slave[0].state = EC_STATE_OPERATIONAL; // TODO правильно ли, что это здесь? // send one valid process data to make outputs in slaves happy ec_send_processdata(); ec_receive_processdata(EC_TIMEOUTRET); // start I/O transfer thread as periodic multimedia timer globalErrorFlag.store(GLOBAL_OK); timerEventId = timeSetEvent(1, 0, ioTransferThread, 0, TIME_PERIODIC); // TODO рассмотреть переход на CreateTimerQueueTimer if (timerEventId == NULL) { qDebug() << "Не удалось создать поток ввода/вывода"; ok = false; } } if (ok) { // request OP state for all slaves ec_writestate(0); // wait for all slaves to reach OP state int chk = 40; do ec_statecheck(0, EC_STATE_OPERATIONAL, 50000); while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL)); if (ec_slave[0].state != EC_STATE_OPERATIONAL) {// не удадось перевести метор в состояние OPERATIONAL qDebug() << "не удадось перевести мотор в состояние OPERATIONAL"; ok = false; } while(EcatError) qDebug("%s", ec_elist2string()); } if (ok) { int result = ec_SDOwrite(1, 0x4003, 0x01, FALSE, sizeof(deviceMode), &deviceMode, EC_TIMEOUTRXM); // Device Mode if (result != 1) qDebug() << "ошибка ec_SDOwrite: " << result; while(EcatError) qDebug("%s", ec_elist2string()); ok = (result == 1); } if (ok) { timer.start(updatePeriod); setPower(true); } else close(); return ok; }