diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..fcbc00c --- /dev/null +++ b/.gitignore @@ -0,0 +1,10 @@ +.vscode + +control_ws/build/ +control_ws/install/ +control_ws/log/ + +eigen_ws/ +fast_lio_ws/ +livox_ws/ +audio_common_ws/ \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..21bb29f --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,78 @@ +{ + "files.associations": { + "*.xacro": "xml", + "iomanip": "cpp", + "cctype": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "csignal": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "array": "cpp", + "atomic": "cpp", + "strstream": "cpp", + "bit": "cpp", + "bitset": "cpp", + "chrono": "cpp", + "codecvt": "cpp", + "compare": "cpp", + "complex": "cpp", + "concepts": "cpp", + "condition_variable": "cpp", + "cstdint": "cpp", + "deque": "cpp", + "forward_list": "cpp", + "list": "cpp", + "map": "cpp", + "set": "cpp", + "string": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "ratio": "cpp", + "regex": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "hash_map": "cpp", + "fstream": "cpp", + "future": "cpp", + "initializer_list": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "new": "cpp", + "numbers": "cpp", + "ostream": "cpp", + "semaphore": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "stop_token": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "cfenv": "cpp", + "cinttypes": "cpp", + "typeindex": "cpp", + "typeinfo": "cpp", + "variant": "cpp" + } +} \ No newline at end of file diff --git a/Arduino/ChainDriveMC5010_2-1.ino b/Arduino/ChainDriveMC5010_2-1.ino deleted file mode 100644 index ff563ff..0000000 --- a/Arduino/ChainDriveMC5010_2-1.ino +++ /dev/null @@ -1,340 +0,0 @@ -//refresh management -int refresh_rate = 20; //[Hz] -int DELAY = (1000 / refresh_rate); - -//variables for movement definition -int Velocity = 0; -int Angle = 0; - -//degrees for Joystick positions -int A = 15; -int B = 45; -int C = 75; -int D = 105; -int E = 135; -int F = 165; - - -//variables for motor controll -int motorStateLeft = 0; -int motorStateRight = 0; - -void setup() { - -//pins for left chain drive - pinMode(13, OUTPUT); - pinMode(12, OUTPUT); - pinMode(11, OUTPUT); - -//pins for right chain drive - pinMode(4, OUTPUT); - pinMode(3, OUTPUT); - pinMode(2, OUTPUT); - - Serial.begin(115200); -} - -void loop() { -//check if Serial connection is good. else stop motors. - if (Serial) { -//receive message via serial connection - String rx_msg = Serial.readStringUntil('\n'); - sscanf(rx_msg.c_str(), "V%iA%i\n", &Velocity, &Angle); - } - else { - Velocity = 0; - Angle = 0; - } - -//-------------------------------------------------------------------------- -//calculate movement state - if(Velocity == 0) { - motorStateRight = 0; - motorStateLeft = 0; - } - else if(Velocity < 30){ -//left semi sircle - if (Angle > ((-1)*A) && Angle < A){ - motorStateRight = 2; - motorStateLeft = 2; - } - else if(Angle >= A && Angle < B){ - motorStateRight = 4; - motorStateLeft = 2; - } - else if(Angle >= B && Angle < C){ - motorStateRight = 4; - motorStateLeft = 0; - } - else if(Angle >= C && Angle < D){ - motorStateRight = 2; - motorStateLeft = 3; - } - else if(Angle >= D && Angle < E){ - motorStateRight = 3; - motorStateLeft = 0; - } - else if(Angle >= E && Angle < F){ - motorStateRight = 5; - motorStateLeft = 3; - } - else if(Angle >= F && Angle <= 180){ - motorStateRight = 3; - motorStateLeft = 3; - } -//right semi circle - else if(Angle <= ((-1)*A) && Angle > ((-1)*B)){ - motorStateRight = 2; - motorStateLeft = 4; - } - else if(Angle <= ((-1)*B) && Angle > ((-1)*C)){ - motorStateRight = 0; - motorStateLeft = 4; - } - else if(Angle <= ((-1)*C) && Angle > ((-1)*D)){ - motorStateRight = 3; - motorStateLeft = 2; - } - else if(Angle <= ((-1)*D) && Angle > ((-1)*E)){ - motorStateRight = 0; - motorStateLeft = 5; - } - else if(Angle <= ((-1)*E) && Angle > ((-1)*F)){ - motorStateRight = 3; - motorStateLeft = 5; - } - else if(Angle <= ((-1)*F) && Angle >= -180){ - motorStateRight = 3; - motorStateLeft = 3; - } - } - else if (Velocity < 70){ -//left semi sircle - if (Angle > ((-1)*A) && Angle < A){ - motorStateRight = 4; - motorStateLeft = 4; - } - else if(Angle >= A && Angle < B){ - motorStateRight = 4; - motorStateLeft = 2; - } - else if(Angle >= B && Angle < C){ - motorStateRight = 4; - motorStateLeft = 0; - } - else if(Angle >= C && Angle < D){ - motorStateRight = 4; - motorStateLeft = 5; - } - else if(Angle >= D && Angle < E){ - motorStateRight = 3; - motorStateLeft = 0; - } - else if(Angle >= E && Angle < F){ - motorStateRight = 5; - motorStateLeft = 3; - } - else if(Angle >= F && Angle <= 180){ - motorStateRight = 5; - motorStateLeft = 5; - } -//right semi circle - else if(Angle <= ((-1)*A) && Angle > ((-1)*B)){ - motorStateRight = 2; - motorStateLeft = 4; - } - else if(Angle <= ((-1)*B) && Angle > ((-1)*C)){ - motorStateRight = 0; - motorStateLeft = 4; - } - else if(Angle <= ((-1)*C) && Angle > ((-1)*D)){ - motorStateRight = 5; - motorStateLeft = 4; - } - else if(Angle <= ((-1)*D) && Angle > ((-1)*E)){ - motorStateRight = 0; - motorStateLeft = 5; - } - else if(Angle <= ((-1)*E) && Angle > ((-1)*F)){ - motorStateRight = 3; - motorStateLeft = 5; - } - else if(Angle <= ((-1)*F) && Angle >= -180){ - motorStateRight = 5; - motorStateLeft = 5; - } - } - else if (Velocity < 120){ -//left semi sircle - if (Angle > ((-1)*A) && Angle < A){ - motorStateRight = 6; - motorStateLeft = 6; - } - else if(Angle >= A && Angle < B){ - motorStateRight = 6; - motorStateLeft = 4; - } - else if(Angle >= B && Angle < C){ - motorStateRight = 6; - motorStateLeft = 2; - } - else if(Angle >= C && Angle < D){ - motorStateRight = 6; - motorStateLeft = 7; - } - else if(Angle >= D && Angle < E){ - motorStateRight = 5; - motorStateLeft = 3; - } - else if(Angle >= E && Angle < F){ - motorStateRight = 7; - motorStateLeft = 5; - } - else if(Angle >= F && Angle <= 180){ - motorStateRight = 7; - motorStateLeft = 7; - } -//right semi circle - else if(Angle <= ((-1)*A) && Angle > ((-1)*B)){ - motorStateRight = 4; - motorStateLeft = 6; - } - else if(Angle <= ((-1)*B) && Angle > ((-1)*C)){ - motorStateRight = 2; - motorStateLeft = 6; - } - else if(Angle <= ((-1)*C) && Angle > ((-1)*D)){ - motorStateRight = 7; - motorStateLeft = 6; - } - else if(Angle <= ((-1)*D) && Angle > ((-1)*E)){ - motorStateRight = 3; - motorStateLeft = 7; - } - else if(Angle <= ((-1)*E) && Angle > ((-1)*F)){ - motorStateRight = 5; - motorStateLeft = 7; - } - else if(Angle <= ((-1)*F) && Angle >= -180){ - motorStateRight = 7; - motorStateLeft = 7; - } - } - else { //ERROR if velocity >120 - motorStateRight = 0; - motorStateLeft = 0; - } - - setRightMode(motorStateRight); - setLeftMode(motorStateLeft); - - Serial.print(motorStateRight); - Serial.print(motorStateLeft); - - delay(DELAY); - -} - -//setting the pins to tell the MC what to do -//left Motor then right Motor -void setLeftMode(int L){ - switch (L){ - case 0: //stop - digitalWrite(13, LOW); - digitalWrite(12, LOW); - digitalWrite(11, LOW); - break; - - case 2: //forward slow - digitalWrite(13, LOW); - digitalWrite(12, HIGH); - digitalWrite(11, LOW); - break; - - case 3: //backwards slow - digitalWrite(13, HIGH); - digitalWrite(12, HIGH); - digitalWrite(11, LOW); - break; - - case 4: //forward medium - digitalWrite(13, LOW); - digitalWrite(12, LOW); - digitalWrite(11, HIGH); - break; - - case 5: //backwards medium - digitalWrite(13, HIGH); - digitalWrite(12, LOW); - digitalWrite(11, HIGH); - break; - - case 6: //forward fast - digitalWrite(13, LOW); - digitalWrite(12, HIGH); - digitalWrite(11, HIGH); - break; - - case 7: //backwards fast - digitalWrite(13, HIGH); - digitalWrite(12, HIGH); - digitalWrite(11, HIGH); - break; - - default: //ERROR -> stop - digitalWrite(13, LOW); - digitalWrite(12, LOW); - digitalWrite(11, LOW); - } -} - -void setRightMode(int R){ - switch (R){ - case 0: //stop - digitalWrite(4, LOW); - digitalWrite(3, LOW); - digitalWrite(2, LOW); - break; - - case 2: //forward slow - digitalWrite(4, LOW); - digitalWrite(3, HIGH); - digitalWrite(2, LOW); - break; - - case 3: //backwards slow - digitalWrite(4, HIGH); - digitalWrite(3, HIGH); - digitalWrite(2, LOW); - break; - - case 4: //forward medium - digitalWrite(4, LOW); - digitalWrite(3, LOW); - digitalWrite(2, HIGH); - break; - - case 5: //backwards medium - digitalWrite(4, HIGH); - digitalWrite(3, LOW); - digitalWrite(2, HIGH); - break; - - case 6: //forward fast - digitalWrite(4, LOW); - digitalWrite(3, HIGH); - digitalWrite(2, HIGH); - break; - - case 7: //backwards fast - digitalWrite(4, HIGH); - digitalWrite(3, HIGH); - digitalWrite(2, HIGH); - break; - - default: //ERROR -> stop - digitalWrite(4, LOW); - digitalWrite(3, LOW); - digitalWrite(2, LOW); - } -} diff --git a/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/Board.cpp b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/Board.cpp new file mode 100644 index 0000000..362c235 --- /dev/null +++ b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/Board.cpp @@ -0,0 +1,949 @@ +/* + * TLE9879_Board.cpp + * + * Created on: 30.05.2017 + * Author: OttJulia + */ + +#include "TLE9879_Group.h" +#include "SPI.h" + +// BEMF PARAMS +// uint16: BEMF_SPIKE_FILT, BEMF_BLANK_FILT, BEMF_POLE_PAIRS, BEMF_SPEED_KP, BEMF_SPEED_KI, BEMF_SPEED_TEST_ENABLE, BEMF_START_FREQ_ZERO +const uint8_t indices_16bit_BEMF[] = {28, 29, 6, 2, 3, 17, 16}; +const uint8_t indices_16bit_BEMF_size = (uint8_t) (sizeof (indices_16bit_BEMF) / sizeof(indices_16bit_BEMF[0])); +// HALL PARAMS +// uint16: HALL_POLE_PAIRS, HALL_INIT_DUTY, HALL_INPUT_A, HALL_INPUT_B, HALL_INPUT_C, HALL_OFFSET_60DEGREE_EN, HALL_ANGLE_DELAY_EN, HALL_DELAY_ANGLE, HALL_DELAY_MINSPEED, HALL_SPEED_KP, HALL_SPEED_KI +const uint8_t indices_16bit_HALL[] = {2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const uint8_t indices_16bit_HALL_size = (uint8_t) (sizeof (indices_16bit_HALL) / sizeof(indices_16bit_HALL[0])); +// FOC PARAMS +// uint16: FOC_SPEED_KP, FOC_SPEED_KI, FOC_CSA_OFFSET, FOC_POLE_PAIRS, FOC_START_FREQ_ZERO +const uint8_t indices_16bit_FOC[] = {10, 11, 28, 29, 38}; +const uint8_t indices_16bit_FOC_size = (uint8_t) (sizeof (indices_16bit_FOC) / sizeof(indices_16bit_FOC[0])); + +const char* const TLE9879_Group::Board::modenames[4] = { "Bootloader", "BEMF", "Hall", "FOC" }; + +// Constructor +TLE9879_Group::Board::Board(uint8_t number, StatusInfo *info) +{ + boardnr = number; + slaveselectpin = number + 3; + status = info; + + // is requested board available? + boardControl(); +} + +TLE9879_Group::Board::~Board() +{ + if (data_FOC) delete data_FOC; + if (data_BEMF) delete data_BEMF; + if (data_HALL) delete data_HALL; +} + +// functions for communication +void TLE9879_Group::Board::sendMessage(uint16_t data) +{ + digitalWrite(slaveselectpin, LOW); // take the SS pin low to select board + delayMicroseconds(100); + SPI.transfer16(data); + delayMicroseconds(100); + digitalWrite(slaveselectpin, HIGH); // take the SS pin high to de-select board + delayMicroseconds(100); +} + +uint16_t TLE9879_Group::Board::readAnswer() +{ + uint16_t receivedMessage = 0; + delayMicroseconds(100); + digitalWrite(slaveselectpin, LOW); + delayMicroseconds(100); + receivedMessage = SPI.transfer16(0x0000); + delayMicroseconds(100); + digitalWrite(slaveselectpin, HIGH); + + return receivedMessage; +} + +boolean TLE9879_Group::Board::sendMessageAndCheckAnswer(uint16_t command) +{ + sendMessage(command); + //delayMicroseconds(100); + uint16_t answer = readAnswer(); + + if(answer == (command + CONFIRM_OFFSET)) return true; + else + { + Serial.print(F("WARNING: Board[")); + Serial.print(boardnr); + Serial.print(F("]; Command[")); + Serial.print(command, HEX); + Serial.print(F("]; Answer[")); + Serial.print(answer, HEX); + Serial.println(F("]")); + return false; + } +} + +boolean TLE9879_Group::Board::isAvailable() +{ + return board_available; +} + +// commands +// 0x01: modeControl +boolean TLE9879_Group::Board::modeControl(uint8_t requestedmode) +{ + // is the board available + if(!isAvailable()) return false; + + // get current mode + if(requestedmode == GETCURRENTMODE) + { + sendMessage(MODECONTROL + GETCURRENTMODE); + uint16_t answer = readAnswer(); + + if((answer == 0x1110) || (answer == 0x1111) || (answer == 0x1112) || (answer == 0x1113)) + { + uint8_t answeredmode = (uint8_t)(answer & 0x000F); + currentmode = answeredmode; + return true; + } + else + { + status->code = ERR_MODE_READING_FAILED; + return false; + } + } + + // already in the requested mode + //if(requestedmode == currentmode) return true; + + // requested mode is not valid + if(requestedmode > 3) + { + status->code = ERR_INVALID_PARAMETER; + status->additionalInfo[0] = (uint16_t) requestedmode; + return false; + } + + // send mode change command + sendMessage(MODECONTROL + requestedmode); + // wait while slave is processing modeControl + + delay(1000); + uint16_t answer = readAnswer(); + if(answer != (MODECONTROL + requestedmode + CONFIRM_OFFSET)) + { + // try to read current mode from TLE9879_Board + delay(1000); + sendMessage(MODECONTROL + GETCURRENTMODE); + delay(100); + uint16_t answer = readAnswer(); + uint16_t successanswer = MODECONTROL + GETCURRENTMODE + requestedmode + CONFIRM_OFFSET; + + // mode change failed + if(answer != successanswer) + { + status->code = ERR_MODE_CHANGE_FAILED; + status->additionalInfo[0] = (uint16_t) currentmode; + status->additionalInfo[1] = (uint16_t) requestedmode; + status->additionalInfo[2] = (uint16_t) answer; + return false; + } + } + + // mode change successful + switch(requestedmode) + { + case FOC: data_FOC = new data_FOC_union(); break; + case BEMF: data_BEMF = new data_BEMF_union(); break; + case HALL: data_HALL = new data_HALL_union(); break; + default: break; + } + currentmode = requestedmode; + return true; +} + +// 0x02: loadDataset +boolean TLE9879_Group::Board::loadDataset(uint8_t datasetnr) +{ + if(!isAvailable()) return false; + if(currentmode == BOOTLOADER) + { + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + } + if(((datasetnr > 3) && (datasetnr < 0x10)) || (datasetnr > 0x13)) + { + status->code = ERR_INVALID_DATASET_NUMBER; + status->additionalInfo[0] = datasetnr; + return false; + } + sendMessage(LOADDATASET + datasetnr); + delay(50); + sendMessage(CHECKSUCCESS); + uint16_t answer = readAnswer(); + + if(answer != LOADDATASET + datasetnr + CONFIRM_OFFSET) + { + status->code = ERR_FAILED; + status->additionalInfo[0] = datasetnr; + return false; + } + return true; +} + +// 0x03: readDataset +uint8_t TLE9879_Group::Board::readDataset() +{ + if(!isAvailable()) return 0; + + // find out mode to decide which dataset needs to be read + boolean success = modeControl(GETCURRENTMODE); + if(!success) + { + status->code = ERR_MODE_READING_FAILED; + return 0; + } + + uint8_t calcCRC, recvCRC; + uint16_t nrofmessages; + uint8_t *uint8ptr; + + switch(currentmode) + { + case BOOTLOADER: + status->code = ERR_STILL_IN_BOOTLOADER; + return 0; + + case BEMF: + sendMessage(READDATASET); + nrofmessages = readAnswer(); + + for(uint8_t i = 0; i < nrofmessages; i++) + { + data_BEMF->dataarray_BEMF[i] = readAnswer(); + } + + uint8ptr = (uint8_t*) data_BEMF; + calcCRC = CRC8(uint8ptr, NUMBEROF_BYTES_BEMF); + recvCRC = (uint8_t)readAnswer(); + break; + + case HALL: + sendMessage(READDATASET); + nrofmessages = readAnswer(); + + for(uint8_t i = 0; i < nrofmessages; i++) + { + data_HALL->dataarray_HALL[i] = readAnswer(); + } + + uint8ptr = (uint8_t*) data_HALL; + calcCRC = CRC8(uint8ptr, NUMBEROF_BYTES_HALL); + recvCRC = (uint8_t)readAnswer(); + break; + + case FOC: + sendMessage(READDATASET); + nrofmessages = readAnswer(); + readAnswer(); + + for(uint8_t i = 0; i < nrofmessages; i++) + { + data_FOC->dataarray_FOC[i] = readAnswer(); + } + + uint8ptr = (uint8_t*) data_FOC; + calcCRC = CRC8(uint8ptr, NUMBEROF_BYTES_FOC); + recvCRC = (uint8_t) readAnswer(); + break; + + default: + return 0; + } + + if(calcCRC != recvCRC) + { + status->code = ERR_CHECKSUM_IS_WRONG; + status->additionalInfo[0] = calcCRC; + status->additionalInfo[1] = recvCRC; + return 0; + } + return 3; +} + +// 0x04: writeDataset +boolean TLE9879_Group::Board::writeDataset(void) +{ + uint8_t nrofmessages = 0, nrofbytes = 0, calcCRC = 0; + uint8_t *uint8ptr; + + if(!isAvailable()) return false; + + boolean success = modeControl(GETCURRENTMODE); + if(!success) + { + status->code = ERR_MODE_READING_FAILED; + return false; + } + + switch(currentmode) + { + case BOOTLOADER: + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + break; + + case BEMF: + nrofmessages = NUMBEROF_MESSAGES_BEMF; + uint8ptr = (uint8_t*)data_BEMF->dataarray_BEMF; + calcCRC = CRC8(uint8ptr, NUMBEROF_BYTES_BEMF); + sendMessage(WRITEDATASET + nrofmessages); + for(int i = 0; i < nrofmessages; i++) + { + sendMessage(data_BEMF->dataarray_BEMF[i]); + } + break; + + case HALL: + nrofmessages = NUMBEROF_MESSAGES_HALL; + uint8ptr = (uint8_t*)data_HALL->dataarray_HALL; + calcCRC = CRC8(uint8ptr, NUMBEROF_BYTES_HALL); + sendMessage(WRITEDATASET + nrofmessages); + for(int i = 0; i < nrofmessages; i++) + { + sendMessage(data_HALL->dataarray_HALL[i]); + } + break; + + case FOC: + nrofmessages = NUMBEROF_MESSAGES_FOC; + uint8ptr = (uint8_t*)data_FOC->dataarray_FOC; + calcCRC = CRC8(uint8ptr, NUMBEROF_BYTES_FOC); + sendMessage(WRITEDATASET + nrofmessages); + for(int i = 0; i < nrofmessages; i++) + { + sendMessage(data_FOC->dataarray_FOC[i]); + } + break; + } + + sendMessage(calcCRC); + delay(50); + sendMessage(CHECKSUCCESS); + uint16_t answer = readAnswer(); + + + if(answer != (WRITEDATASET + nrofmessages + CONFIRM_OFFSET)) + { + status->code = ERR_FAILED_ANSWER; + status->additionalInfo[0] = answer; + status->additionalInfo[1] = WRITEDATASET + nrofmessages + CONFIRM_OFFSET; + return false; + } + else return true; +} + +// 0x05: changeParameter +boolean TLE9879_Group::Board::changeParameter(uint8_t index, float data) +{ + if(!isAvailable()) return false; + + boolean datacheckOK = false, dataIsUint16; + boolean success = modeControl(GETCURRENTMODE); + if(!success) + { + status->code = ERR_MODE_READING_FAILED; + return false; + } + + switch(currentmode) + { + case BOOTLOADER: + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + + case BEMF: + // no offset at index + if(index >= HALLOFFSET) + { + status->code = ERR_INVALID_PARAMETER_INDEX; + status->additionalInfo[0] = (uint16_t) BEMF; + status->additionalInfo[1] = (uint16_t) index; + return false; + } + dataIsUint16 = isvalueinarray(index, indices_16bit_BEMF, indices_16bit_BEMF_size); + break; + + case HALL: + // offset between HALLOFFSER and FOCOFFSET at index + if((index < HALLOFFSET) || index > FOCOFFSET) + { + status->code = ERR_INVALID_PARAMETER_INDEX; + status->additionalInfo[0] = (uint16_t) HALL; + status->additionalInfo[1] = (uint16_t) index; + return false; + } + index -= HALLOFFSET; + dataIsUint16 = isvalueinarray(index, indices_16bit_HALL, indices_16bit_HALL_size); + break; + + case FOC: + // offset FOCOFFSET at index + if(index < FOCOFFSET) + { + status->code = ERR_INVALID_PARAMETER_INDEX; + status->additionalInfo[0] = (uint16_t) FOC; + status->additionalInfo[1] = (uint16_t) index; + return false; + } + index -= FOCOFFSET; + dataIsUint16 = isvalueinarray(index, indices_16bit_FOC, indices_16bit_FOC_size); + break; + } + + if (dataIsUint16) // 16bit variable + { + uint16_t uint16val = (uint16_t)(data); + datacheckOK = checkuint16val(currentmode, index, &uint16val); + if(datacheckOK) + { + sendMessage(CHANGEPARAMETER + index); + sendMessage((uint16_t)uint16val); + } + else return false; + } + else + { + uint32_t *uint32ptr = (uint32_t*) &data; + datacheckOK = checkfloatval(currentmode, index, &data); + if(datacheckOK) + { + sendMessage(CHANGEPARAMETER + index); + sendMessage((uint16_t)((*uint32ptr)>>16)); + sendMessage((uint16_t)(*uint32ptr)); + } + else return false; + } + + delay(50); + sendMessage(CHECKSUCCESS); + uint16_t answer = readAnswer(); + if(answer != CHANGEPARAMETER + index + CONFIRM_OFFSET) + { + status->code = ERR_FAILED; + return false; + } + return true; +} +// 0x06: saveDataset +boolean TLE9879_Group::Board::saveDataset(uint8_t position) +{ + if(!isAvailable()) return false; + + if(currentmode == BOOTLOADER) + { + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + } + + if(position > 3) + { + status->code = ERR_INVALID_DATASET_NUMBER; + status->additionalInfo[0] = position; + return false; + } + + sendMessage(SAVEDATASET + position); + delay(50); + sendMessage(CHECKSUCCESS); + uint16_t answer = readAnswer(); + + if(answer != SAVEDATASET + position + CONFIRM_OFFSET) + { + status->code = ERR_FAILED_ANSWER; + status->additionalInfo[0] = answer; + status->additionalInfo[1] = SAVEDATASET + position + CONFIRM_OFFSET; + return false; + } + return true; +} + +// 0x07: setMotorspeed +boolean TLE9879_Group::Board::setMotorspeed(float motorspeed) +{ + if(!isAvailable()) return false; + if(currentmode == BOOTLOADER) + { + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + } + + sendMessage(SETMOTORSPEED); + sendMessage((int16_t)motorspeed); + + delay(50); + sendMessage(CHECKSUCCESS); + uint16_t answer = readAnswer(); + + if(answer != SETMOTORSPEED +CONFIRM_OFFSET) + { + status->code = ERR_FAILED; + return false; + } + this->motorspeed = motorspeed; + return true; +} + +// 0x08: motorControl- +boolean TLE9879_Group::Board::motorControl(uint8_t command) +{ + if(!isAvailable()) return false; + if(currentmode == BOOTLOADER) + { + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + } + if((command != START_MOTOR) && (command != STOP_MOTOR)) + { + status->code = ERR_INVALID_PARAMETER; + status->additionalInfo[0] = command; + return false; + } + sendMessage(MOTORCONTROL+command); + delay(50); + sendMessage(CHECKSUCCESS); + uint16_t answer = readAnswer(); + + if(answer != MOTORCONTROL + command + CONFIRM_OFFSET) + { + status->code = ERR_FAILED; + Serial.print(F("WARNING: Board[")); + Serial.print(boardnr); + Serial.print(F("]; Command[")); + Serial.print(command, HEX); + Serial.print(F("]; Answer[")); + Serial.print(answer, HEX); + Serial.println(F("]")); + return false; + } + return true; +} + +// 0x09: boardControl +boolean TLE9879_Group::Board::boardControl() +{ + // board available? + boolean success = sendMessageAndCheckAnswer(BOARDCONTROL + BOARD_AVAILABLE); + board_available = success; + return success; +} + +// 0x0A: LEDOn +boolean TLE9879_Group::Board::LEDOn(uint8_t led) +{ + if(!isAvailable()) + return false; + + if((led != LED_RED) && (led != LED_GREEN) && (led != LED_BLUE)) + { + Serial.println(F("Requested LED was not valid. Valid LEDs are: LED_RED, LED_GREEN, LED_BLUE")); + return false; + } + boolean success = sendMessageAndCheckAnswer(LED_ON + led); + return success; +} + +// 0x0B: LEDOff +boolean TLE9879_Group::Board::LEDOff(uint8_t led) +{ + if(!isAvailable()) + return false; + + if((led != LED_RED) && (led != LED_GREEN) && (led != LED_BLUE)) + { + Serial.println(F("Requested LED was not valid. Valid LEDs are: LED_RED, LED_GREEN, LED_BLUE")); + return false; + } + boolean success = sendMessageAndCheckAnswer(LED_OFF + led); + return success; +} + +//0x0F: getMotorspeed +int16_t TLE9879_Group::Board::getMotorspeed() +{ + if(!isAvailable()) return false; + if(currentmode == BOOTLOADER) + { + status->code = ERR_STILL_IN_BOOTLOADER; + return false; + } + + sendMessage(GETMOTORSPEED); + act_speed = readAnswer(); + Serial.print(F("INFO: Speed Of Motor")); + Serial.print(boardnr); + Serial.print(F("->")); + Serial.println(act_speed); + return true; +} + +/** + * Reads the HALL Bit pattern from TLE9879QXA40's CCU6 CMPSTAT register + * @returns The 3-Bit pattern of the HALL sensor + * @author Beatrix Dietl + */ +uint16_t TLE9879_Group::Board::readHallPattern() +{ + if (!isAvailable()) return false; + + sendMessage(READHALLPATTERN); + uint16_t hallPattern = readAnswer(); // Read Hall pattern + /* + Serial.print(F("INFO: Hall Pattern Of Motor")); + Serial.print(boardnr); + Serial.print(F(" -> ")); + for (int i = 2; i >= 0; i--) { + Serial.print(bitRead(hallPattern, i)); + } + Serial.println(); + */ + return hallPattern; +} + +uint8_t TLE9879_Group::Board::isvalueinarray(uint8_t val, const uint8_t *indices_16bit_BEMF, const uint8_t size) +{ + int i; + for (i=0; i < size; i++) + { + if (indices_16bit_BEMF[i] == val) + { + return 1; + } + } + return 0; +} + +//CRC-8 - based on the CRC8 formulas by Dallas/Maxim +//code released under the therms of the GNU GPL 3.0 license +//at http://www.leonardomiliani.com/en/2013/un-semplice-crc8-per-arduino/ +uint8_t TLE9879_Group::Board::CRC8(uint8_t *data, uint8_t len) +{ + uint8_t crc = 0x55; + while (len--) + { + uint8_t extract = *data++; + for (uint8_t tempI = 8; tempI; tempI--) + { + uint8_t sum = (crc ^ extract) & 0x01; + crc >>= 1; + if (sum) + { + crc ^= 0x8C; + } + extract >>= 1; + } + } + return crc; +} + +boolean TLE9879_Group::Board::checkuint16val(uint8_t mode, uint8_t index, uint16_t *data) +{ + switch(mode) + { + case BEMF: + switch(index) + { + case BEMF_START_FREQ_ZERO: // 1/0 + if(*data > 0) *data = 1; break; + case BEMF_SPEED_TEST_ENABLE: // 1/0 + if(*data > 0) *data = 1; break; + case BEMF_SPIKE_FILT: // code 1/2/4/8 + switch (*data) + { + case 1: *data = 0; break; + case 2: *data = 1; break; + case 4: *data = 2; break; + case 8: *data = 3; break; + default: + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_SPIKE_FILT. Valid values are: 1, 2, 4, 8")); + return false; + } + break; + case BEMF_BLANK_FILT: // code 3/6/8/12/16 + switch (*data) + { + case 3: *data = 4; break; + case 6: *data = 0; break; + case 8: *data = 1; break; + case 12: *data = 2; break; + case 16: *data = 3; break; + default: + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_BLANK_FILT. Valid values are: 3, 6, 8, 12, 16")); + return false; + } + break; + } + break; + case HALL: + switch(index) + { + case HALL_INIT_DUTY: // 0-100 + if((*data < 0) || (*data > 100)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_INIT_DUTY. Valid values are: 0-100")); + return false; + } + break; + case HALL_INPUT_A: // 0/1/2 + if(*data > 2) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_INPUT_A. Valid values are: 0/1/2")); + return false; + } + break; + case HALL_INPUT_B: // 0/1/2 + if(*data > 2) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_INPUT_B. Valid values are: 0/1/2")); + return false; + } + break; + case HALL_INPUT_C: // 0/1/2 + if(*data > 2) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_INPUT_C. Valid values are: 0/1/2")); + return false; + } + break; + case HALL_OFFSET_60DEGREE_EN: // 0/1 + if(*data > 1) *data = 1; break; + case HALL_ANGLE_DELAY_EN: // 0/1 + if(*data > 1) *data = 1; break; + case HALL_DELAY_ANGLE: // 0-59 + if(*data > 59) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_DELAY_ANGLE. Valid values are: 0-59")); + return false; + } + break; + case HALL_DELAY_MINSPEED: // 0-2000 + if(*data > 2000) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_DELAY_MINSPEED. Valid values are: 0-2000")); + return false; + } + break; + } + break; + case FOC: + switch(index) + { + case FOC_SPEED_KP: // >0 + if(*data == 0) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_SPEED_KP. Valid values are: >0")); + return false; + } + break; + case FOC_SPEED_KI: // >0 + if(*data == 0) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_SPEED_KI. Valid values are: >0")); + return false; + } + break; + case FOC_START_FREQ_ZERO: // 0/1 + if(*data > 1) *data = 1; break; + } + break; + } + return true; +} + +boolean TLE9879_Group::Board::checkfloatval(uint8_t mode, uint8_t index, float *data) +{ + switch(mode) + { + case BEMF: + switch(index) + { + case BEMF_TIME_CONST_SPEED_FILT_TIME: // 0.01-1 + if((*data < 0.01) || (*data > 1)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_SPEED_FILT_TIME. Valid values are: 0.01-1.")); + return false; + } + break; + case BEMF_START_SPEED_PWM_MIN: // 0-0.95 + if((*data < 0) || (*data > 0.95)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_START_SPEED_PWM_MIN_OFFSET. Valid values are: 0-0.95.")); + return false; + } + break; + case BEMF_START_SPEED_PWM_MIN_OFFSET: // 0-0.95 + if((*data < 0) || (*data > 0.95)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_START_SPEED_PWM_MIN_OFFSET. Valid values are: 0-0.95.")); + return false; + } + break; + case BEMF_SPEED_BEGIN_PWM_MIN: // 0-0.95 + if((*data < 0) || (*data > 0.95)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_RUN_SPEED_PWM_MIN. Valid values are: 0-0.95.")); + return false; + } + break; + case BEMF_SPEED_PWM_MIN: // 0-0.95 + if((*data < 0) || (*data > 0.95)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for BEMF_END_SPEED_PWM_MIN. Valid values are: 0-0.95.")); + return false; + } + break; + } + break; + + case HALL: + switch(index) + { + case HALL_SPEED_IMIN: // 0-100 + if((*data < 0) || (*data > 100)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_SPEED_IMIN. Valid values are: 0-100.")); + return false; + } + break; + case HALL_SPEED_IMAX: // 0-100 + if((*data < 0) || (*data > 100)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_SPEED_IMAX. Valid values are: 0-100.")); + return false; + } + break; + case HALL_SPEED_PIMIN: // 0-100 + if((*data < 0) || (*data > 100)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_SPEED_PIMIN. Valid values are: 0-100.")); + return false; + } + break; + case HALL_SPEED_PIMAX: // 0-100 + if((*data < 0) || (*data > 100)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for HALL_SPEED_PIMAX. Valid values are: 0-100.")); + return false; + } + break; + } + break; + + case FOC: + switch(index) + { + case FOC_CUR_ADJUST: // 0.01-1 + if((*data < 0.01) || (*data > 1)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_CUR_ADJUST. Valid values are: 0.01-1")); + return false; + } + break; + case FOC_FLUX_ADJUST: // 0.01-1 + if((*data < 0.01) || (*data > 1)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_FLUX_ADJUST. Valid values are: 0.01-1")); + return false; + } + break; + case FOC_SPEED_FILT_TIME: // 0.01-1 + if((*data < 0.01) || (*data > 1)) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_SPEED_FILT_TIME. Valid values are: 0.01-1")); + return false; + } + break; + case FOC_MIN_NEG_REF_CUR: // <0 + if(*data > 0) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_MIN_NEG_REF_CUR. Valid values are: <0")); + return false; + } + break; + case FOC_MIN_CUR_SPEED: // <0 + if(*data > 0) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_MIN_CUR_SPEED. Valid values are: <0")); + return false; + } + break; + case FOC_MAX_NEG_REF_CUR: // <0 + if(*data > 0) + { + Serial.print(F("Invalid value '")); + Serial.print(*data); + Serial.println(F("' for FOC_MAX_NEG_REF_CUR. Valid values are: <0")); + return false; + } + break; + } + break; + } + return true; +} + +uint8_t TLE9879_Group::Board::getCurrentMode() +{ + return currentmode; +} diff --git a/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/ResQBot_FlipperPosition_NEW_090525_copy_20250512.ino b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/ResQBot_FlipperPosition_NEW_090525_copy_20250512.ino new file mode 100644 index 0000000..ab9ada7 --- /dev/null +++ b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/ResQBot_FlipperPosition_NEW_090525_copy_20250512.ino @@ -0,0 +1,286 @@ +#include "TLE9879_Group.h" +#include +#include + +// ———————————————————————— +// CONFIGURATION +// ———————————————————————— +static const uint8_t MAX_MOTORS = 4; +static const uint8_t MOTOR_COUNT = 4; +static const uint8_t BOARD_ID[MAX_MOTORS] = { BOARD1, BOARD2, BOARD3, BOARD4 }; + +static const int16_t STOP_DELAY = 5; // ms per motor stop +static const int16_t REFRESH_RATE = 20; // Hz +static const int16_t DELAY_MS = (1000 / REFRESH_RATE) - (STOP_DELAY * MOTOR_COUNT); + +static const int16_t DEFAULT_SPEED = 2900; // motor‐speed scale + +static const unsigned long PRINT_INTERVAL = 50; // ms +static const unsigned long POLL_INTERVAL = 1; // ms +static const unsigned long ERROR_THRESHOLD = 1000; // ms + +// mechanical / Hall constants +static const int16_t FHBLDC_HALL_POLE_PAIRS = 2; +static const float GEAR_RATIO = 44.0f; +static const float WORM_GEAR_RATIO = 10.0f; +static const float TOTAL_GEAR_RATIO = 44.0f; +static const float CORRECTION_FACTOR = 1.2f; +static const float STEP_ELEC = 60.0f; +static const float STEP_CORR = STEP_ELEC * CORRECTION_FACTOR; +static const float TRANS_PER_OUT = (360.0f * FHBLDC_HALL_POLE_PAIRS * TOTAL_GEAR_RATIO) / STEP_CORR; + +// ———————————————————————— +// GLOBALS +// ———————————————————————— +TLE9879_Group *shields; + +// drive state +int16_t commanded[MAX_MOTORS]; +int16_t modeState[MAX_MOTORS]; + +// estimator state +unsigned long lastPollTime[MAX_MOTORS]; +unsigned long lastPrintTime[MAX_MOTORS]; +unsigned long lastTransTime[MAX_MOTORS]; +unsigned long transPeriod[MAX_MOTORS]; +int32_t reportCount[MAX_MOTORS]; +float lastDiscAngle[MAX_MOTORS]; +int8_t lastIdx[MAX_MOTORS]; // zuletzt gesehenes Hall-Sektorfeld (0-5) + +// Hall readings buffer +uint16_t hallBuf[MAX_MOTORS]; + +// ———————————————————————— +// ANGLE HELPERS +// ———————————————————————— +float normalizeAngle(float a) { + float x = fmod(a, 360.0f); + return (x < 0) ? x + 360.0f : x; +} + +float getCounterClockwiseElectricalAngle(uint16_t hallPattern) { + switch (hallPattern) { + case 0b010: return 0.0f; + case 0b011: return 60.0f; + case 0b001: return 120.0f; + case 0b101: return 180.0f; + case 0b100: return 240.0f; + case 0b110: return 300.0f; + default: return -1.0f; + } +} + +float getClockwiseElectricalAngle(uint16_t hallPattern) { + switch (hallPattern) { + case 0b001: return 0.0f; + case 0b011: return 60.0f; + case 0b010: return 120.0f; + case 0b110: return 180.0f; + case 0b100: return 240.0f; + case 0b101: return 300.0f; + default: return -1.0f; + } +} + +// ———————————————————————— +// TRANSITION HANDLING +// ———————————————————————— +void handleTransition(int i, float currAng, unsigned long now) +{ + // 0°, 60°, … 300° → Index 0 … 5 + int8_t currIdx = (int)round(currAng / STEP_ELEC) % 6; + + if (lastIdx[i] < 0) { // erster gültiger Messwert + lastIdx[i] = currIdx; + lastTransTime[i] = now; + return; + } + + /* -------- sichtbare Schrittweite 0 … ±5 -------- */ + int8_t diff; + if (modeState[i] > 0) diff = (currIdx - lastIdx[i] + 6) % 6; // CCW + else if (modeState[i] < 0) diff = -((lastIdx[i] - currIdx + 6) % 6); // CW + else diff = 0; + + /* -------- Fall 1: Index hat sich geändert -------- */ + if (diff != 0) { + unsigned long dt = now - lastTransTime[i]; + unsigned long stepTime = dt / abs(diff); // Zeit für **eine** Flanke + + reportCount[i] += diff; // ± sichtbare Schritte + transPeriod[i] = stepTime; // neue Referenz­periode + lastTransTime[i] = now; + lastIdx[i] = currIdx; + return; + } + + /* -------- Fall 2: Index gleich ⇒ evtl. ganze 6er-Pakete verpasst -------- */ + if (transPeriod[i] == 0) return; // noch keine Referenz + + unsigned long dt = now - lastTransTime[i]; + uint32_t missed = dt / transPeriod[i]; // geschätzte Flanken + + if (missed == 0) return; // zu wenig Zeit vergangen + + int8_t sgn = (modeState[i] > 0) ? 1 : (modeState[i] < 0 ? -1 : 0); + reportCount[i] += sgn * missed; // alle fehlenden Flanken addieren + lastTransTime[i] += missed * transPeriod[i]; // Zeitbasis nachführen +} + + + + +bool checkMotorError(int i, unsigned long now) { + if (now - lastTransTime[i] > ERROR_THRESHOLD) { + Serial.print("[ERROR] Motor "); + Serial.print(i); + Serial.println(" stuck or no hall!"); + return true; + } + return false; +} + +float computeTotalElec(int i, unsigned long now) { + float frac = 0; + if (transPeriod[i] > 0) { + frac = float(now - lastTransTime[i]) / transPeriod[i]; + if (frac > 1.0f) frac = 1.0f; + } + float tot = reportCount[i] + frac; + float m = fmod(tot, TRANS_PER_OUT); + return m * STEP_CORR; +} + +float electricalToMechanical(float e) { + return e / FHBLDC_HALL_POLE_PAIRS; +} + +float motorToOutputAngle(float mech) { + return mech / TOTAL_GEAR_RATIO; +} + +// ———————————————————————— +// SETUP +// ———————————————————————— +void setup() { + Serial.begin(115200); + while (!Serial); + + shields = new TLE9879_Group(1); + + // initialize each enabled board + for (int i = 0; i < MOTOR_COUNT; i++) { + uint8_t b = BOARD_ID[i]; + shields->setMode(HALL, b); + shields->setParameter(HALL_PWM_FREQ, 20000, b); + shields->setParameter(HALL_POLE_PAIRS, 2, b); + shields->setParameter(HALL_SPEED_IMIN, 0, b); + shields->setParameter(HALL_SPEED_IMAX, 29, b); + shields->setParameter(HALL_SPEED_PIMIN, 0, b); + shields->setParameter(HALL_SPEED_PIMAX, 29, b); + shields->setParameter(HALL_OFFSET_60DEGREE_EN, 1, b); + shields->setMotorSpeed(0, b); + shields->setMotorMode(START_MOTOR, b); + } + + unsigned long t0 = millis(); + // clear all slots + for (int i = 0; i < MAX_MOTORS; i++) { + commanded[i] = 0; + modeState[i] = 0; + lastPollTime[i] = t0; + lastPrintTime[i] = t0; + lastTransTime[i] = t0; + transPeriod[i] = 0; + reportCount[i] = 0; + lastDiscAngle[i] = -1.0f; + lastIdx[i] = -1; // <— NEU + } +} + +// ———————————————————————— +// MAIN LOOP +// ———————————————————————— +void loop() { + // 1) Read serial for up to MOTOR_COUNT values + if (Serial.available()) { + String rx = Serial.readStringUntil('\n'); + int tmp[MAX_MOTORS] = {0,0,0,0}; + sscanf(rx.c_str(), "FL%iFR%iRL%iRR%i", + &tmp[0], &tmp[1], &tmp[2], &tmp[3]); + for (int i = 0; i < MOTOR_COUNT; i++) { + commanded[i] = tmp[i]; + } + } + + /* + // 2) Flip rear motors (indices 2 and 3) if they exist + for (int i = 2; i < MOTOR_COUNT; i++) { + commanded[i] *= -1; + } + */ + + unsigned long now = millis(); + + // 3) Drive & mode transitions + for (int i = 0; i < MOTOR_COUNT; i++) { + uint8_t b = BOARD_ID[i]; + if (commanded[i] == modeState[i]) { + delay(STOP_DELAY); + } else { + shields->setMotorMode(STOP_MOTOR, b); // only when needed + delay(STOP_DELAY); + shields->setMotorMode(START_MOTOR, b); // ENABLE the bridge first + delay(1); // HW needs ≥ 1 µs, be generous + shields->setMotorSpeed(commanded[i] * DEFAULT_SPEED, b); + modeState[i] = commanded[i]; + } + } + + // 4) Read all enabled Hall patterns + shields->readHallPatterns(hallBuf); + + // 5) Position estimation + print + for (int i = 0; i < MOTOR_COUNT; i++) { + // a) poll sensor + if (now - lastPollTime[i] >= POLL_INTERVAL) { + lastPollTime[i] = now; + float ang = (modeState[i] > 0) + ? getCounterClockwiseElectricalAngle(hallBuf[i]) + : (modeState[i] < 0) + ? getClockwiseElectricalAngle(hallBuf[i]) + : -1.0f; + if (ang >= 0) { + handleTransition(i, ang, now); + checkMotorError(i, now); + } + } + } + // b) print every PRINT_INTERVAL + static unsigned long lastPrintTimeGlobal = 0; // NEW + + if (now - lastPrintTimeGlobal >= PRINT_INTERVAL) { + lastPrintTimeGlobal = now; + + String line = ""; + + + for (int i = 0; i < MOTOR_COUNT; ++i) { + float elec = computeTotalElec(i, now); + float mech = electricalToMechanical(elec); + float out = motorToOutputAngle(mech); + const char* pfx = (i == 0 ? "FL" + : i == 1 ? "FR" + : i == 2 ? "RL" + : "RR"); + + line += pfx; + line += String((int)round(normalizeAngle(out))); + } + + Serial.println(line); // print the whole line once + } + + // 6) enforce overall loop rate + delay(DELAY_MS); +} diff --git a/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/TLE9879_Group.cpp b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/TLE9879_Group.cpp new file mode 100644 index 0000000..0276bbf --- /dev/null +++ b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/TLE9879_Group.cpp @@ -0,0 +1,600 @@ +/* + * TLE9879_Group.cpp + * + * Created on: 19.02.2018 + * Author: Haidari, Ahmad + */ + +#include "TLE9879_Group.h" +#include "Arduino.h" +#include "SPI.h" + +TLE9879_Group::TLE9879_Group(uint8_t boardCount) +{ + this->boardCount = boardCount; + + // start serial connection with a baud rate of 9600 + //Serial.begin(115200); + + //Serial.println(F("INFO: Starting initialization")); + + // set the auto-addressing pin to high + pinMode(8, OUTPUT); + digitalWrite(8, HIGH); + + // set all the slave-select-pins to high (not selected) + pinMode(SLAVESELECT_BOARD1, OUTPUT); + pinMode(SLAVESELECT_BOARD2, OUTPUT); + pinMode(SLAVESELECT_BOARD3, OUTPUT); + pinMode(SLAVESELECT_BOARD4, OUTPUT); + digitalWrite(SLAVESELECT_BOARD1, HIGH); + digitalWrite(SLAVESELECT_BOARD2, HIGH); + digitalWrite(SLAVESELECT_BOARD3, HIGH); + digitalWrite(SLAVESELECT_BOARD4, HIGH); + + delay(500); + + // start the SPI connection + SPI.begin(); + SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE3)); + + // all boards are reset and set to bootloader mode + resetAllBoards(); + delay(500); + + // Here, the given number of boards is initialized. + // The initialization command is send repeatedly, until exactly the given number of boards are ready to be used, + // i.e. if any board does not respond positively, the command is send again and again, until it responds. + // This means the program will be stuck in a loop in case one board is not properly attached or does not work properly. + for(int i = 0; i < boardCount; i++) + { + // create board object + boards[i] = new Board(i + 1, status); + + // if the board is not available wait 2 seconds and try again + while(!boards[i]->isAvailable()) + { + delay(2000); + if(status->code != ERR_NONE) processStatusCodes(BOARDCONTROL, i + 1); + boards[i]->boardControl(); + } + + //Serial.print(F("INFO: Board ")); + //Serial.print(i + 1); + //Serial.println(F(" was successfully initialized")); + } + + //Serial.println(F("INFO: Done initializing")); + delay(100); +} + +TLE9879_Group::~TLE9879_Group() +{ + for(int i = 0; i < 4; i++) if(boards[i]) delete boards[i]; + delete status; +} + +void TLE9879_Group::sendMessageToAll(uint16_t data) +{ + // select all four boards simultaneously + digitalWrite(SLAVESELECT_BOARD1, LOW); + digitalWrite(SLAVESELECT_BOARD2, LOW); + digitalWrite(SLAVESELECT_BOARD3, LOW); + digitalWrite(SLAVESELECT_BOARD4, LOW); + + // send the message to all boards + delayMicroseconds(100); + SPI.transfer16(data); + delayMicroseconds(100); + + // deselect all four boards + digitalWrite(SLAVESELECT_BOARD1, HIGH); + digitalWrite(SLAVESELECT_BOARD2, HIGH); + digitalWrite(SLAVESELECT_BOARD3, HIGH); + digitalWrite(SLAVESELECT_BOARD4, HIGH); + delayMicroseconds(100); +} + +void TLE9879_Group::loadDataset(uint8_t pos, uint8_t boardnr) +{ + uint8_t index, end; + if(!checkBoardNumber(boardnr, LOADDATASET, index, end)) return; + + for( ; index < end; index++) + { + boards[index]->loadDataset(pos); + processStatusCodes(LOADDATASET, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: load dataset complete -> ")); + printBoardNr(boardnr); + //Serial.println(pos); + } +} + +void TLE9879_Group::saveDataset(uint8_t pos, uint8_t boardnr) +{ + //pos -= CUSTOMDATASET0; // custom datasets start at 0x10 instead of 0x00 + + uint8_t index, end; + if(!checkBoardNumber(boardnr, SAVEDATASET, index, end)) return; + + for( ; index < end; index++) + { + boards[index]->saveDataset(pos); + processStatusCodes(SAVEDATASET, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: save dataset complete -> ")); + printBoardNr(boardnr); + //Serial.println(pos); + } +} + +void TLE9879_Group::readDataset(uint8_t boardnr) +{ + if(boardnr > ALL_BOARDS || boardnr == 0) + { + status->code = ERR_INVALID_BOARD_NR; + status->additionalInfo[0] = boardnr; + } + + uint8_t index, end; + if(!checkBoardNumber(boardnr, READDATASET, index, end)) return; + + for( ; index < end; index++) + { + boards[index]->readDataset(); + processStatusCodes(READDATASET, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: read dataset complete -> ")); + printBoardNr(boardnr); + //Serial.println(""); + } +} + +void TLE9879_Group::writeDataset(uint8_t boardnr) +{ + uint8_t index, end; + if(!checkBoardNumber(boardnr, WRITEDATASET, index, end)) return; + + for( ; index < end; index++) + { + boards[index]->writeDataset(); + processStatusCodes(WRITEDATASET, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: write dataset complete -> ")); + printBoardNr(boardnr); + //Serial.println(); + } +} + +void TLE9879_Group::copyDataset(uint8_t mode, uint8_t from, uint8_t to) +{ + from--; + + if(mode == FOC || mode == BEMF || mode == HALL) + { + uint8_t index, end; + if(!checkBoardNumber(to, COPYDATASET, index, end)) return; + if(from > BOARD4 - 1) + { + status->code = ERR_INVALID_BOARD_NR; + status->additionalInfo[0] = from; + } else + { + for( ; index < end; index++) + { + if(index == from) continue; + + switch(mode) + { + case FOC: boards[index]->data_FOC->datastruct_FOC = boards[from]->data_FOC->datastruct_FOC; break; + case BEMF: (*boards[index]->data_BEMF) = (*boards[from]->data_BEMF); break; + case HALL: (*boards[index]->data_HALL) = (*boards[from]->data_HALL); break; + } + } + } + } else + { + status->code = ERR_INVALID_PARAMETER; + status->additionalInfo[0] = mode; + } + + processStatusCodes(COPYDATASET, 0); + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: copy dataset complete -> ")); + printBoardNr(to); + //Serial.println(); + } +} + +void TLE9879_Group::setParameter(uint8_t parameter, float value, uint8_t boardnr) +{ + uint8_t index, end; + if(!checkBoardNumber(boardnr, CHANGEPARAMETER, index, end)) return; + + for( ; index < end; index++) + { + boards[index]->changeParameter(parameter, value); + processStatusCodes(CHANGEPARAMETER, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: parameter change complete -> ")); + printBoardNr(boardnr); + //Serial.print(F("parameter: ")); + //Serial.print(parameter); + //Serial.print(F("; value: ")); + //Serial.println(value); + } +} + +void TLE9879_Group::setMotorMode(uint8_t mode, uint8_t boardnr) +{ + if (mode > STOP_MOTOR) + { + status->code = ERR_INVALID_PARAMETER; + status->additionalInfo[0] = mode; + return; + } + + uint8_t index, end; + if (!checkBoardNumber(boardnr, MOTORCONTROL, index, end)) return; + + for ( ; index < end; index++) + { + boards[index]->motorControl(mode); + processStatusCodes(MOTORCONTROL, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: motor mode change complete -> ")); + printBoardNr(boardnr); + //if (mode == START_MOTOR) Serial.println(F("start")); + //else //Serial.println(F("stop")); + } +} + +void TLE9879_Group::setMotorSpeed(float motorspeed, uint8_t boardnr) +{ + uint8_t index, end; + if(!checkBoardNumber(boardnr, SETMOTORSPEED, index, end)) return; + + for( ; index < end; index++) + { + boards[index]->setMotorspeed(motorspeed); + processStatusCodes(SETMOTORSPEED, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: motor speed change complete -> ")); + printBoardNr(boardnr); + //Serial.println(motorspeed); + } +} + +void TLE9879_Group::getMotorSpeed(uint8_t boardnr) +{ + //Serial.print(F("Get motor speed started:")); + uint8_t index, end; + if(!checkBoardNumber(boardnr, GETMOTORSPEED, index, end)) return; + // uint16_t speed_answer=0; + for( ; index < end; index++) + { + boards[index]->getMotorspeed(); + processStatusCodes(GETMOTORSPEED, index + 1); + } +} + +void TLE9879_Group::setMode(uint8_t mode, uint8_t boardnr, bool fastMode) +{ + uint8_t index, end; + if(!checkBoardNumber(boardnr, MODECONTROL, index, end)) return; + + if(fastMode) + { + sendMessageToAll(MODECONTROL + mode); + delay(1000); + for( ; index < end; index++) + { + boards[index]->modeControl(GETCURRENTMODE); + if(boards[index]->getCurrentMode() != mode) + { + status->code = ERR_MODE_CHANGE_FAILED; + status->additionalInfo[0] = (uint16_t) boards[index]->getCurrentMode(); + status->additionalInfo[1] = (uint16_t) mode; + status->additionalInfo[2] = (uint16_t) 0; + processStatusCodes(MODECONTROL, index + 1); + } + } + } else + { + for( ; index < end; index++) + { + boards[index]->modeControl(mode); + processStatusCodes(MODECONTROL, index + 1); + } + } + + if(infoMessagesEnabled) + { + //Serial.print(F("INFO: mode change complete -> ")); + printBoardNr(boardnr); + //if(mode == GETCURRENTMODE) Serial.println(F("Get Current Mode")); + //else Serial.println(Board::modenames[mode]); + } +} + +void TLE9879_Group::setLed(uint16_t led, uint16_t mode, uint8_t boardnr) +{ + uint8_t index, end; + if(!checkBoardNumber(boardnr, LED, index, end)) return; + + for( ; index < end; index++) + { + if(mode == LED_ON) boards[index]->LEDOn(led); + else if(mode == LED_OFF) boards[index]->LEDOff(led); + processStatusCodes(LED, index + 1); + } + + if(infoMessagesEnabled) + { + //Serial.println(F("INFO: LED control complete")); + } +} + +void TLE9879_Group::setLedColor(uint8_t color, uint8_t boardnr) +{ + // blue LED + if(color & 1) setLed(LED_BLUE, LED_ON, boardnr); + else setLed(LED_BLUE, LED_OFF, boardnr); + + // green LED + if(color & 2) setLed(LED_GREEN, LED_ON, boardnr); + else setLed(LED_GREEN, LED_OFF, boardnr); + + // red LED + if(color & 4) setLed(LED_RED, LED_ON, boardnr); + else setLed(LED_RED, LED_OFF, boardnr); +} + +void TLE9879_Group::startAutoAddressing() +{ + //Serial.println(F("INFO: Doing auto-addressing")); + sendMessageToAll(BOARDCONTROL + AUTOADDRESSING); + delay(100); // let slaves do auto-addressing +} + +void TLE9879_Group::resetAllBoards() +{ + //Serial.println(F("INFO: Sending reset request to all boards")); + // stop all motors (they may be running) + sendMessageToAll(MOTORCONTROL + STOP_MOTOR); + delay(10); + // reset all TLE9879_Boards + sendMessageToAll(BOARDCONTROL + RESET); + delay(1000); +} + +void TLE9879_Group::checkErrors() +{ + static unsigned long time = 0; + + if(millis() - time < 1000) return; + + for(int i = 0; i < boardCount; i++) + { + if(!boards[i]) continue; + + boards[i]->sendMessage(CHECK_ERROR); + uint16_t answer = boards[i]->readAnswer(); + if(answer != CHECK_ERROR + CONFIRM_OFFSET) + { + //Serial.print(F("WARNING: Error Checks; Board: ")); + //Serial.print(i + 1); + //Serial.print(F("; Mode: ")); + //Serial.print(Board::modenames[boards[i]->getCurrentMode()]); + //Serial.print(F("; Error code: ")); + + for(uint16_t i = 1; i <= 0x1000; i *= 2) + { + if((i & answer) != 0) + { + //Serial.print(i, HEX); + //Serial.print(F(", ")); + } + } + //Serial.print(F("answer: ")); + //Serial.println(answer, HEX); + } + } + + time = millis(); +} + +/* +TLE9879_Group::Board* TLE9879_Group::getBoard(uint8_t index) +{ + if(index > BOARD4) return nullptr; + return boards[index - 1]; +} +*/ + +void TLE9879_Group::processStatusCodes(uint16_t action, uint8_t boardnr) +{ + if(status->code == ERR_NONE) return; + //Serial.print(F("WARNING: Board[")); + //Serial.print(boardnr); + //Serial.print(F("]; Action[")); + printAction(action); + //Serial.print(F("]; ")); + + switch(status->code) + { + case ERR_STILL_IN_BOOTLOADER: + //Serial.println(F("action cannot be performed in bootloader")); + break; + case ERR_CHECKSUM_IS_WRONG: + //Serial.print(F("checksum does not match -> calc: ")); + //Serial.print(status->additionalInfo[0]); + //Serial.print(F("; recv: ")); + //Serial.println(status->additionalInfo[1]); + break; + case ERR_NOT_AVAILABLE: + //Serial.println(F("not available")); + break; + case ERR_MODE_READING_FAILED: + //Serial.println(F("mode could not be read")); + break; + case ERR_MODE_CHANGE_FAILED: + //Serial.print(F("failed -> from ")); + //Serial.print(Board::modenames[status->additionalInfo[0]]); + //Serial.print(F(" to ")); + //Serial.print(Board::modenames[status->additionalInfo[1]]); + //Serial.print(F("; Answer: ")); + //Serial.println(status->additionalInfo[2], HEX); + break; + case ERR_INVALID_DATASET_NUMBER: + //Serial.print(F("the dataset number was invalid -> ")); + //Serial.println(status->additionalInfo[0]); + break; + case ERR_INVALID_PARAMETER_INDEX: + //Serial.print(F("parameter index is invalid -> ")); + //Serial.print(Board::modenames[status->additionalInfo[0]]); + //Serial.print(F("; ")); + //Serial.println(status->additionalInfo[1]); + break; + case ERR_FAILED: + //Serial.println(F("failed")); + break; + case ERR_INVALID_PARAMETER: + //Serial.print(F("the given parameter is invalid -> ")); + //Serial.println(status->additionalInfo[0]); + break; + case ERR_INVALID_BOARD_NR: + //Serial.print(F("the given boardnr is invalid ->")); + //Serial.println(boardnr); + break; + case ERR_FAILED_ANSWER: + //Serial.print(F("shield failed to confirm successful command -> answer: 0x")); + //Serial.print(status->additionalInfo[0], HEX); + //Serial.print(F(", expected: 0x")); + //Serial.println(status->additionalInfo[1], HEX); + break; + default: + //Serial.print(F("Error code is not available ->")); + //Serial.println(status->code); + break; + } + + status->code = ERR_NONE; +} + +void TLE9879_Group::printAction(uint16_t action) +{ + //switch(action) + //{ + // case MODECONTROL: Serial.print(F("mode control")); break; + // case LOADDATASET: Serial.print(F("load dataset")); break; + // case READDATASET: Serial.print(F("read dataset")); break; + // case WRITEDATASET: Serial.print(F("write dataset")); break; + // case CHANGEPARAMETER: Serial.print(F("change parameter")); break; + // case SAVEDATASET: Serial.print(F("save dataset")); break; + // case SETMOTORSPEED: Serial.print(F("set motor speed")); break; + // case MOTORCONTROL: Serial.print(F("motor control")); break; + // case BOARDCONTROL: Serial.print(F("board control")); break; + // case COPYDATASET: Serial.print(F("copy dataset")); break; + // case LED: Serial.print(F("LED control")); break; + // default: break; + //} +} + +bool TLE9879_Group::checkBoardNumber(uint8_t boardnr, uint16_t action, uint8_t& startIndex, uint8_t& endIndex) +{ + if(boardnr > ALL_BOARDS) + { + status->code = ERR_INVALID_BOARD_NR; + processStatusCodes(action, boardnr); + return false; + } else if(boardnr == ALL_BOARDS) + { + startIndex = 0; + endIndex = boardCount; + } else + { + startIndex = boardnr - 1; + endIndex = boardnr; + } + return true; +} + +void TLE9879_Group::printBoardNr(uint8_t boardnr) +{ + if(boardnr == ALL_BOARDS) Serial.print(F("Board: All; ")); + //else + //{ + //Serial.print(F("Board: ")); + //Serial.print(boardnr); + //Serial.print(F("; ")); + //} +} + +void TLE9879_Group::testBlinky() +{ + static uint8_t index = 0; + static long timerBlinky = 0; + + if(millis() - timerBlinky > 1000) + { + index++; + if(index > COLOR_MAX_NUMBER) + { + index = 0; + } + + setLedColor(index); + timerBlinky = millis(); + } +} + +/** + * Reads the HALL Bit pattern from TLE9879QXA40's CCU6 CMPSTAT register from a specified board or all boards if not specifiec + * @returns The 3-Bit pattern of the HALL sensor + * @author Beatrix Dietl + */ +uint16_t TLE9879_Group::readHallPattern(uint8_t boardnr) +{ + uint8_t index, end; + if (!checkBoardNumber(boardnr, READHALLPATTERN, index, end)) return; + + uint16_t hallPattern = 0; // Store hall state + for (; index < end; index++) // Loop through selected boards + { + hallPattern = boards[index]->readHallPattern(); // Read Hall pattern + processStatusCodes(READHALLPATTERN, index + 1); + } + + return hallPattern; +} + +void TLE9879_Group::readHallPatterns(uint16_t* buffer) { + for (uint8_t i = 1; i <= boardCount; i++) { + buffer[i-1] = readHallPattern(i); + } +} diff --git a/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/TLE9879_Group.h b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/TLE9879_Group.h new file mode 100644 index 0000000..732a2e4 --- /dev/null +++ b/Arduino/ResQBot_FlipperPosition_NEW_090525_copy_20250512/TLE9879_Group.h @@ -0,0 +1,443 @@ +/* + * TLE9879_Group.h + * + * Created on: 19.02.2018 + * Author: Haidari, Ahmad + */ + +#ifndef TLE9879_FOURPACK_H_ +#define TLE9879_FOURPACK_H_ + +#include "Arduino.h" + +typedef bool boolean; + +// --------------------DEFINES-------------------- +// Constructor +#define BOARD1 1 +#define BOARD2 2 +#define BOARD3 3 +#define BOARD4 4 +#define ALL_BOARDS 5 + +// common +#define CONFIRM_OFFSET 0x1000 +#define SLAVESELECT_BOARD1 4 +#define SLAVESELECT_BOARD2 5 +#define SLAVESELECT_BOARD3 6 +#define SLAVESELECT_BOARD4 7 + +// 0x01: modeControl +#define MODECONTROL 0x0100 +#define BOOTLOADER 0x00 +#define BEMF 0x01 +#define HALL 0x02 +#define FOC 0x03 +#define GETCURRENTMODE 0x10 + +// 0x02: loadDataset +#define LOADDATASET 0x0200 +#define DATASET0 0x00 +#define DATASET1 0x01 +#define DATASET2 0x02 +#define DATASET3 0x03 +#define CUSTOMDATASET0 0x10 +#define CUSTOMDATASET1 0x11 +#define CUSTOMDATASET2 0x12 +#define CUSTOMDATASET3 0x13 + +// 0x03: readDataset +#define READDATASET 0x0300 + +// 0x04: writeDataset +#define WRITEDATASET 0x0400 +#define NUMBEROF_MESSAGES_FOC (46u) +#define NUMBEROF_MESSAGES_BEMF (30u) +#define NUMBEROF_MESSAGES_HALL (22u) +#define NUMBEROF_BYTES_FOC (NUMBEROF_MESSAGES_FOC * 2u) +#define NUMBEROF_BYTES_BEMF (NUMBEROF_MESSAGES_BEMF * 2u) +#define NUMBEROF_BYTES_HALL (NUMBEROF_MESSAGES_HALL * 2u) + +// 0x05: changeParameter +#define CHANGEPARAMETER 0x0500 +// BEMF parameter: 0...29 +#define BEMF_PWM_FREQ 0 +#define BEMF_SPEED_KP 2 +#define BEMF_SPEED_KI 3 +#define BEMF_TIME_CONST_SPEED_FILT_TIME 4 +#define BEMF_POLE_PAIRS 6 +#define BEMF_RESERVED_PADDING 7 +#define BEMF_ZERO_VEC_TIME 8 +#define BEMF_END_START_SPEED 10 +#define BEMF_START_ACCEL 12 +#define BEMF_RUN_ACCEL 14 +#define BEMF_START_FREQ_ZERO 16 +#define BEMF_SPEED_TEST_ENABLE 17 +#define BEMF_SWITCH_ON_SPEED 18 +#define BEMF_START_SPEED_PWM_MIN 20 +#define BEMF_START_SPEED_PWM_MIN_OFFSET 22 +#define BEMF_SPEED_BEGIN_PWM_MIN 24 +#define BEMF_SPEED_PWM_MIN 26 +#define BEMF_SPIKE_FILT 28 +#define BEMF_BLANK_FILT 29 + +// Hall parameter: 30...52 +#define HALLOFFSET 30 +#define HALL_PWM_FREQ (0+HALLOFFSET) +#define HALL_POLE_PAIRS (2+HALLOFFSET) +#define HALL_INIT_DUTY (3+HALLOFFSET) +#define HALL_INPUT_A (4+HALLOFFSET) +#define HALL_INPUT_B (5+HALLOFFSET) +#define HALL_INPUT_C (6+HALLOFFSET) +#define HALL_OFFSET_60DEGREE_EN (7+HALLOFFSET) +#define HALL_ANGLE_DELAY_EN (8+HALLOFFSET) +#define HALL_DELAY_ANGLE (9+HALLOFFSET) +#define HALL_DELAY_MINSPEED (10+HALLOFFSET) +#define HALL_SPEED_KP (11+HALLOFFSET) +#define HALL_SPEED_KI (12+HALLOFFSET) +#define HALL_RESERVED_PADDING (13+HALLOFFSET) +#define HALL_SPEED_IMIN (14+HALLOFFSET) +#define HALL_SPEED_IMAX (16+HALLOFFSET) +#define HALL_SPEED_PIMIN (18+HALLOFFSET) +#define HALL_SPEED_PIMAX (20+HALLOFFSET) + +// FOC parameter: 52...98 +#define FOCOFFSET 52 +#define FOC_R_SHUNT (0+FOCOFFSET) +#define FOC_NOM_CUR (2+FOCOFFSET) +#define FOC_PWM_FREQ (4+FOCOFFSET) +#define FOC_R_PHASE (6+FOCOFFSET) +#define FOC_L_PHASE (8+FOCOFFSET) +#define FOC_SPEED_KP (10+FOCOFFSET) +#define FOC_SPEED_KI (11+FOCOFFSET) +#define FOC_MAX_POS_REF_CUR (12+FOCOFFSET) +#define FOC_MAX_NEG_REF_CUR (14+FOCOFFSET) +#define FOC_MIN_POS_REF_CUR (16+FOCOFFSET) +#define FOC_MIN_NEG_REF_CUR (18+FOCOFFSET) +#define FOC_MAX_CUR_SPEED (20+FOCOFFSET) +#define FOC_MIN_CUR_SPEED (22+FOCOFFSET) +#define FOC_SPEED_FILT_TIME (24+FOCOFFSET) +#define FOC_FLUX_ADJUST (26+FOCOFFSET) +#define FOC_POLE_PAIRS (29+FOCOFFSET) +#define FOC_START_CUR_IF (30+FOCOFFSET) +#define FOC_ZERO_VEC_TIME (32+FOCOFFSET) +#define FOC_END_START_SPEED (34+FOCOFFSET) +#define FOC_START_ACCEL (36+FOCOFFSET) +#define FOC_START_FREQ_ZERO (38+FOCOFFSET) +#define FOC_RESERVED (39+FOCOFFSET) +#define FOC_SWITCH_ON_SPEED (40+FOCOFFSET) +#define FOC_CUR_ADJUST (42+FOCOFFSET) +#define FOC_MAX_SPEED (44+FOCOFFSET) + +#define FOC_CSA_OFFSET (28+FOCOFFSET) + +// 0x06: saveDataset +#define SAVEDATASET 0x0600 +#define POSITION0 0 +#define POSITION1 1 +#define POSITION2 2 +#define POSITION3 3 + +// 0x07: setMotorspeed +#define SETMOTORSPEED 0x0700 + +// 0x08: motorControl +#define MOTORCONTROL 0x0800 +#define START_MOTOR 0x00 +#define STOP_MOTOR 0x01 + +// 0x09: boardControl +#define BOARDCONTROL 0x0900 +#define AUTOADDRESSING 0x00 +#define BOARD_AVAILABLE 0x01 +#define RESET 0x02 + +// 0x0A: LEDOn +#define LED 0x0E00 +#define LED_ON 0x0A00 +#define LED_RED 0x02 +#define LED_GREEN 0x03 +#define LED_BLUE 0x13 +#define COLOR_BLACK 0x00 +#define COLOR_BLUE 0x01 +#define COLOR_GREEN 0x02 +#define COLOR_TURQUOISE 0x03 +#define COLOR_RED 0x04 +#define COLOR_PURPLE 0x05 +#define COLOR_YELLOW 0x06 +#define COLOR_WHITE 0x07 +#define COLOR_MAX_NUMBER 0x07 + +// 0x0B: LEDOff +#define LED_OFF 0x0B00 + +// 0x0C: Check for error +#define CHECK_ERROR 0x0C00 +#define ERR_NONE 0x00 +#define ERR_STILL_IN_BOOTLOADER 0x01 +#define ERR_CHECKSUM_IS_WRONG 0x02 +#define ERR_NOT_AVAILABLE 0x03 +#define ERR_MODE_READING_FAILED 0x04 +#define ERR_MODE_CHANGE_FAILED 0x05 +#define ERR_INVALID_DATASET_NUMBER 0x06 +#define ERR_INVALID_PARAMETER_INDEX 0x07 +#define ERR_FAILED 0x08 +#define ERR_INVALID_PARAMETER 0x09 +#define ERR_INVALID_BOARD_NR 0x0A +#define ERR_FAILED_ANSWER 0x0B + +#define COPYDATASET 0x0D00 + +// 0x0F: getMotorspeed +#define GETMOTORSPEED 0x0F00 + +// 0x11: CHECKSUCCESS +#define CHECKSUCCESS 0x1100 + +// 0x1111: SUCCESS +#define SUCCESS 0x1111 + +/** + * 0x55: readHallPattern + * @author Beatrix Dietl + */ +#define READHALLPATTERN 0x5500 + +// Error Handling Structure +typedef struct +{ + uint8_t code = ERR_NONE; // possible error code of a function + uint16_t additionalInfo[5] = { 0, 0, 0, 0, 0 }; // additional info can be stored here +} StatusInfo; + + +// --------------------DATATYPES-------------------- +// ----------BEMF---------- +typedef struct +{ + float PWM_Frequency; /* PWM Frequency */ + uint16_t SpeedPi_Kp; /* Speedcontroller Kp *64 */ + uint16_t SpeedPi_Ki; /* Speedcontroller Ki */ + float TimeConstantSpeedFilter; /* Time constant for Speedfilter*/ + uint16_t PolePair; /* Pol Pair counter */ + uint16_t ReservedForPadding; /* For memory alignment purposes */ + float TimeSpeedzero; /* Time for Speed zero */ + float StartSpeedEnd; /* Max Speed for Start */ + float StartSpeedSlewRate; /* Start Speed SlewRate */ + float RunSpeedSlewRate; /* Run Speed SlewRate */ + uint16_t EnableFrZero; /* Enable Start width Frequenz=0*/ + uint16_t SpeedTestEnable; /* Enable Speedtest*/ + float SpeedLevelSwitchOn; /* Speedlevel for switch on */ + float StartSpeedPwmMin; /* Speed pwm start min */ + float StartSpeedPwmMinOffset; /* Speed pwm start min offset*/ + float SpeedBeginPwmMin; /* Speed pwm run min */ + float SpeedPwmMin; /* Speed pwm run min */ +} TEmo_Bemfpar_Cfg; + +typedef struct +{ + TEmo_Bemfpar_Cfg emocfg_BEMF; + uint16_t spike_filt; + uint16_t blank_filt; +} Tdatastruct_BEMF; + +typedef union +{ + uint16_t dataarray_BEMF[NUMBEROF_MESSAGES_BEMF]; + Tdatastruct_BEMF datastruct_BEMF; +} data_BEMF_union; + +// ----------HALL---------- +typedef struct +{ + float PWM_Frequency; + uint16_t PolePair; + uint16_t initDutyCycle; + uint16_t inputA; + uint16_t inputB; + uint16_t inputC; + uint16_t offset60degEn; + uint16_t angleDelayEn; + uint16_t delayAngle; + uint16_t delayMinspeed; + uint16_t SpeedPi_Kp; + uint16_t SpeedPi_Ki; + uint16_t ReservedForPadding; + float speedIMin; + float speedIMax; + float speedPiMin; + float speedPiMax; +} TEmo_Hallpar_Cfg; + +typedef union +{ + uint16_t dataarray_HALL[NUMBEROF_MESSAGES_HALL]; + TEmo_Hallpar_Cfg datastruct_HALL; +} data_HALL_union; + +// ----------FOC---------- +typedef struct +{ + float Rshunt; + float NominalCurrent; /* Nominal Current */ + float PWM_Frequency; /* PWM Frequency */ + float PhaseRes; /* brief Phase resistance */ + float PhaseInd; /* Phase inductance */ + uint16_t SpeedPi_Kp; /* Speedcontroller Kp *64 */ + uint16_t SpeedPi_Ki; /* Speedcontroller Ki */ + float MaxRefCurr; /* MaxRefCurrent for SpeedController */ + float MinRefCurr; /* MinRefCurrent for SpeedController */ + float MaxRefStartCurr; /* MaxRefCurrent for SpeedController by Start*/ + float MinRefStartCurr; /* MinRefCurrent for SpeedController by Start*/ + float SpeedLevelPos; /* SpeedLevel for MaxRefCurrent for SpeedController by Start*/ + float SpeedLevelNeg; /* SpeedLevel for MinRefCurrent for SpeedController by Start*/ + float TimeConstantSpeedFilter; /* Time constant for Speedfilter*/ + float TimeConstantEstFluxFilter; /* Time constant for estimator flux */ + uint16_t CsaOffset; /* Offset of current sense amplifier */ + uint16_t PolePair; /* Pol Pair counter */ + float StartCurrent; /* Start Current */ + float TimeSpeedzero; /* Time for Speed zero */ + float StartSpeedEnd; /* Max Speed for Start */ + float StartSpeedSlewRate; /* Start Speed SlewRate */ + uint16_t EnableFrZero; /* Enable Start width Frequenz=0*/ + uint16_t reserved; + float SpeedLevelSwitchOn; /* Speedlevel for switch on */ + float AdjustmCurrentControl; /* Adjustment for CurrentControl */ + float MaxSpeed; /* Maximum Speed */ +} TEmo_Focpar_Cfg; + + +typedef union +{ + uint16_t dataarray_FOC[NUMBEROF_MESSAGES_FOC]; + TEmo_Focpar_Cfg datastruct_FOC; +} data_FOC_union; + +class TLE9879_Group +{ +private: + class Board; + + Board* boards[4] = { nullptr, nullptr, nullptr, nullptr }; + StatusInfo* status = new StatusInfo(); + uint8_t boardCount; + + void processStatusCodes(uint16_t action, uint8_t boardnr); + void printAction(uint16_t action); + bool checkBoardNumber(uint8_t boardnr, uint16_t action, uint8_t& startIndex, uint8_t& endIndex); + void printBoardNr(uint8_t boardnr); + +public: + bool infoMessagesEnabled = true; + + TLE9879_Group(uint8_t boardCount); + ~TLE9879_Group(); + + void startAutoAddressing(); + void resetAllBoards(); + void setMode(uint8_t mode, uint8_t boardnr = ALL_BOARDS, bool fastMode = false); + void setMotorMode(uint8_t mode, uint8_t boardnr = ALL_BOARDS); + void setMotorSpeed(float motorspeed, uint8_t boardnr = ALL_BOARDS); + void getMotorSpeed(uint8_t boardnr = ALL_BOARDS); + void setParameter(uint8_t parameter, float value, uint8_t boardnr = ALL_BOARDS); + void saveDataset(uint8_t pos, uint8_t boardnr = ALL_BOARDS); + void loadDataset(uint8_t pos, uint8_t boardnr = ALL_BOARDS); + void readDataset(uint8_t boardnr = ALL_BOARDS); + void writeDataset(uint8_t boardnr = ALL_BOARDS); + void copyDataset(uint8_t mode, uint8_t from, uint8_t to = ALL_BOARDS); + void sendMessageToAll(uint16_t data); + void setLed(uint16_t led, uint16_t mode, uint8_t boardnr = ALL_BOARDS); + void setLedColor(uint8_t color, uint8_t boardnr = ALL_BOARDS); + void checkErrors(); + void testBlinky(); + /** + * readHallPattern functionality + * @author Beatrix Dietl + */ + uint16_t readHallPattern(uint8_t boardnr = ALL_BOARDS); + void readHallPatterns(uint16_t* buffer); + // Board* getBoard(uint8_t index); +}; + +class TLE9879_Group::Board +{ +private: + uint8_t boardnr = 0; + uint8_t slaveselectpin = 0; + uint8_t currentmode = 0; + boolean board_available = false; + + int16_t motorspeed = 0; + //recieved speed + int16_t act_speed=0; + StatusInfo* status; +public: + data_FOC_union* data_FOC = nullptr; + data_BEMF_union* data_BEMF = nullptr; + data_HALL_union* data_HALL = nullptr; + + static const char* const modenames[4]; + + Board(uint8_t number, StatusInfo* info); // constructor + ~Board(); // destructor + + // functions for communication + void sendMessage(uint16_t data); // select slave, send, deselect slave + uint16_t readAnswer(); + boolean sendMessageAndCheckAnswer(uint16_t command); + boolean isAvailable(); + //void start(); + + // commands + // 0x01: modeControl + boolean modeControl(uint8_t mode); + + // 0x02: loadDataset + boolean loadDataset(uint8_t datasetnr); + + //0x03: readDataset + uint8_t readDataset(void); + + // 0x04: writeCompleteDataset + boolean writeDataset(void); + + // 0x05: changeParameter + boolean changeParameter(uint8_t index, float data); + + // 0x06: saveDataset + boolean saveDataset(uint8_t position); + + // 0x07: setMotorspeed + boolean setMotorspeed(float motorspeed); + + // 0x08: motorControl + boolean motorControl(uint8_t command); + + // 0x09: autoAddressing + boolean boardControl(); + + // 0x0A: LEDOn + boolean LEDOn(uint8_t led); + + // 0x0B: LEDOff + boolean LEDOff(uint8_t led); + + //0X0F: getMotorspeed + int16_t getMotorspeed(); + + /** + * readHallPattern functionality, parameter 0x55 + * @author Beatrix Dietl + */ + uint16_t readHallPattern(); + + // additional functions + uint8_t isvalueinarray(uint8_t val, const uint8_t* indices_16bit, const uint8_t size); + uint8_t CRC8(uint8_t* data, uint8_t len); + boolean checkuint16val(uint8_t mode, uint8_t index, uint16_t* data); + boolean checkfloatval(uint8_t mode, uint8_t index, float* data); + uint8_t getCurrentMode(); + //boolean reset(); +}; + +#endif diff --git a/Arduino/serial-flipper_1-2.ino b/Arduino/serial-flipper_1-2.ino deleted file mode 100644 index 0691982..0000000 --- a/Arduino/serial-flipper_1-2.ino +++ /dev/null @@ -1,172 +0,0 @@ -#include -//Baudrate is defined in the TLE Library - -// Shield-Gruppenobjekt -TLE9879_Group *shields; - -// FrontLeft_Board = BOARD4; -// FrontRight_Board = BOARD1; -// RearLeft_Board = BOARD3; -// RearRight_Board = BOARD2; - -//variables for connection -int16_t stop_delay = 10; -int16_t refresh_rate = 20; //[Hz] -int16_t DELAY = (1000 / refresh_rate) - stop_delay; //delay between two loops according to refresh_rate - -//variables for movement controll -int16_t FrontLeft = 0; -int16_t FrontRight = 0; -int16_t RearLeft = 0; -int16_t RearRight = 0; -int16_t default_speed = 2900; - -int16_t FrontLeft_mode = 0; -int16_t FrontRight_mode = 0; -int16_t RearLeft_mode = 0; -int16_t RearRight_mode = 0; - -void setup(){ - - // Initialize the Shield group object with the number of Shields in the stack - shields = new TLE9879_Group(4); - - // Set the desired mode (FOC, HALL, BEMF) - shields->setMode(HALL, BOARD4); - shields->setMode(HALL, BOARD3); - shields->setMode(HALL, BOARD2); - shields->setMode(HALL, BOARD1); - - //Set Hall Frequency - shields->setParameter(HALL_PWM_FREQ, 20000, BOARD4); //[kHz] - shields->setParameter(HALL_PWM_FREQ, 20000, BOARD3); //[kHz] - shields->setParameter(HALL_PWM_FREQ, 20000, BOARD2); //[kHz] - shields->setParameter(HALL_PWM_FREQ, 20000, BOARD1); //[kHz] - - //set number of pole pairs (look up in data sheet) - shields->setParameter(HALL_POLE_PAIRS, 2, BOARD4); - shields->setParameter(HALL_POLE_PAIRS, 2, BOARD3); - shields->setParameter(HALL_POLE_PAIRS, 2, BOARD2); - shields->setParameter(HALL_POLE_PAIRS, 2, BOARD1); - - //set minimum I value (must be 0 to enable motor speed = 0) - shields->setParameter(HALL_SPEED_IMIN, 0, BOARD4); - shields->setParameter(HALL_SPEED_IMIN, 0, BOARD3); - shields->setParameter(HALL_SPEED_IMIN, 0, BOARD2); - shields->setParameter(HALL_SPEED_IMIN, 0, BOARD1); - - //set max I value (indirectly restricts max current) - shields->setParameter(HALL_SPEED_IMAX, 29, BOARD4); - shields->setParameter(HALL_SPEED_IMAX, 29, BOARD3); - shields->setParameter(HALL_SPEED_IMAX, 29, BOARD2); - shields->setParameter(HALL_SPEED_IMAX, 29, BOARD1); - - //set min P value (must be 0 to enable motor speed = 0) - shields->setParameter(HALL_SPEED_PIMIN, 0, BOARD4); - shields->setParameter(HALL_SPEED_PIMIN, 0, BOARD3); - shields->setParameter(HALL_SPEED_PIMIN, 0, BOARD2); - shields->setParameter(HALL_SPEED_PIMIN, 0, BOARD1); - - //set max P value (indirectly restricts max current) - shields->setParameter(HALL_SPEED_PIMAX, 29, BOARD4); - shields->setParameter(HALL_SPEED_PIMAX, 29, BOARD3); - shields->setParameter(HALL_SPEED_PIMAX, 29, BOARD2); - shields->setParameter(HALL_SPEED_PIMAX, 29, BOARD1); - - /* - //proportional gain in the PI controller formula - shields->setParameter(HALL_SPEED_KP, 500, BOARD4); - - //integral gain in the PI controller formula - shields->setParameter(HALL_SPEED_KI, 100, BOARD4); - - //shields->setLed(LED_ON, BOARD4); - shields->setLedColor(COLOR_BLUE, BOARD4); - */ - - shields->setMotorSpeed(0, BOARD4); - shields->setMotorSpeed(0, BOARD3); - shields->setMotorSpeed(0, BOARD2); - shields->setMotorSpeed(0, BOARD1); - - shields->setMotorMode(START_MOTOR, BOARD4); - shields->setMotorMode(START_MOTOR, BOARD3); - shields->setMotorMode(START_MOTOR, BOARD2); - shields->setMotorMode(START_MOTOR, BOARD1); - -} - -void loop(){ -//check if Serial connection is good. If not, stop motors. - if (Serial) { -//receive message via serial connection - String rx_msg = Serial.readStringUntil('\n'); - sscanf(rx_msg.c_str(), "FL%iFR%iRL%iRR%i\n", &FrontLeft, &FrontRight, &RearLeft, &RearRight); - } - else { - FrontLeft = 0; - FrontRight = 0; - RearLeft = 0; - RearRight = 0; - } - -//correction for motor orientation - RearLeft = RearLeft * -1; - RearRight = RearRight * -1; - -//set front left motor speed - if (FrontLeft == FrontLeft_mode) { - delay(stop_delay); - } - else { - shields->setMotorMode(STOP_MOTOR, BOARD4); - delay(stop_delay); - shields->setMotorSpeed(FrontLeft * default_speed, BOARD4); - shields->setMotorMode(START_MOTOR, BOARD4); - FrontLeft_mode = FrontLeft; - } - -//set front right motor speed - if (FrontRight == FrontRight_mode) { - delay(stop_delay); - } - else { - shields->setMotorMode(STOP_MOTOR, BOARD1); - delay(stop_delay); - shields->setMotorSpeed(FrontRight * default_speed, BOARD1); - shields->setMotorMode(START_MOTOR, BOARD1); - FrontRight_mode = FrontRight; - } - -//set rear left motor speed - if (RearLeft == RearLeft_mode) { - delay(stop_delay); - } - else { - shields->setMotorMode(STOP_MOTOR, BOARD3); - delay(stop_delay); - shields->setMotorSpeed(RearLeft * default_speed, BOARD3); - shields->setMotorMode(START_MOTOR, BOARD3); - RearLeft_mode = RearLeft; - } - -//set rear right motor speed - if (RearRight == RearRight_mode) { - delay(stop_delay); - } - else { - shields->setMotorMode(STOP_MOTOR, BOARD2); - delay(stop_delay); - shields->setMotorSpeed(RearRight * default_speed, BOARD2); - shields->setMotorMode(START_MOTOR, BOARD2); - RearRight_mode = RearRight; - } - -/* if the new command is the same as the current motion -> do nothing - * else stop the motor for a short interval and set the new speed, then restart the motor. - * stopping the motor allows for residual current to be dispersed and fixes a problem with reversing the motor's direction. - */ - -//delay until next cycle - delay(DELAY); -} diff --git a/README.md b/README.md deleted file mode 100644 index 42f651d..0000000 --- a/README.md +++ /dev/null @@ -1,6 +0,0 @@ -# resqbot_dev - -used packages: -joy -usb_cam -image_transport diff --git a/Res.Q_Bots_Setup.md b/Res.Q_Bots_Setup.md new file mode 100644 index 0000000..e94ab69 --- /dev/null +++ b/Res.Q_Bots_Setup.md @@ -0,0 +1,778 @@ +## Res.Q Bots Setup + +Dieses Tutorial ist eine Schritt für Schritt Anleitung, um die komplette Softwaresuite des Res.Q Bots Teams einzurichten und mit dem Coden zu starten. + +**Disclaimer:** This REEADME is meant for internal use by Res.Q Bots members. While we do not forbid anyone else from using it, we want to caution you, that this file is not complete and updated infrequently. It is by no means a reliable source to work with, if you are not in direct contact with one of the people who have been working on it. Most of the packages used are open source packages developrd by other people, who know what they are doing way better than us. +We have done our best to link to the original GitHubs for any non standard ROS packages. + + + +## Inhalt + +1. [Ubuntu Grundlagen](#0-ubuntu-terminals) +2. [Betriebssystem](#1-betriebssystem) +3. [ROS Installation](#2-ros2-humble) +4. [ROS Packages](#3-ros-packages) + - [Package Liste](#package-liste) + - [Packages installieren und einrichten](#packages-installieren-und-einrichten) +5. [Arduino Packages](#4-arduino-packages) + +## 1. Betriebssystem + +### 1.1 Raspberry Pi 5 + +**RaspberryPi Imager** installieren: + + sudo apt update + sudo apt install rpi-imager + +**Imager** starten und Image auf SD-Karte spielen: + + Raspberry Pi Device = Raspberry Pi 5 + Operating System = Other General Purpose OS -> Ubuntu -> Ubuntu Server 24.04 LTS + Storage = SD-Karte + +Mit ```Next``` weiter, dann ```EDDIT SETTINGS```. + +Im Reiter ```GENERAL```: + + Set hostname: sinnvollen Namen auswählen + + Set username and password + Username: resqbots + Password: resq + + Configure wireless LAN + SSID: ResQBots_5G + Password: Res.QBots + + Set locale settings + Time zone: Europe/Vienna + Keyboard layout: de + +Im Reiter ```SERVICES```: + + Enable SSH + Use password authentication + +```Save``` und mit ```YES``` bestätigen. Den Warnhinweis mit ```YES``` bestätigen und der Prozess startet. Dies kann einige Zeit dauern. Ist der Prozess beendet, die Karte aus dem Rechner entnehmen und in den Raspi stecken. Dann den Raspi starten. + +  + +### 1.2 PC + +**Ubuntu 24.04 LTS** Image von Ubuntu Website downloaden. + +USB-Startmedium erstellen: +**Rufus**, **Balena-Etcher**, oder ein Ähnliches Tool downloaden und starten. Den Anleitungen folgen. Hier kann nicht viel falsch gemacht werden, solange **Ubuntu 24.04 Desktop** als image gewählt wird. + +#### Dual-Boot einrichten +Dieser Abschnitt folg noch + +  + +## 2. Ubuntu Terminals +Ein sehr vereinfachtes und unvollständiges Intro in die **Linux Shell**, das den Umgang mit **Befehlsterminals** lehren und erklären soll. +In Ubuntu lässt sich fast alles mit Terminalbefehlen erledigen. Gerade fürs Programmieren und den Umgang mit ROS ist es von enormer Bedeutung das Terminal nutzen zu können. + +  + +### 2.1 Terminal UI +Die Tastenkombination ```Strg```+```Alt```+```T``` öffnet ein neues Terminal. Links in der aktuellen Zeile wird angezeigt, welcher **User** den Befehl ausführt, auf welchem **Host** der Befehl ausgeführt wird und in welchem **Verzeichnis** man sich gerade befindet, z.B.: + + resqbots@Q-T-Pi:~$ echo "hello world" + +**resqbots** ist der **User** + +**Q-T-Pi** ist der **Host** ( = das Gerät auf dem der User angemeldet ist) + +**~** ist default Verzeichnis beim einloggen + +**$** ist ein Trennsymbol, danach fängt der Befehl an + +```echo "hello world"``` ist der Befehl, der ausgeführt werden soll + +  + +### 2.2 Wichtige Befehle + +### Strg + C +Die Tastenkombination ```Strg``` + ```C``` bricht den aktuell laufenden Prozess ab. Dies ist besonders wichtig, um ROS-Packages zu stoppen. + +### cd + +```cd ``` wechselt vom aktuellen Verzeichnis in das gewälte Unterverzeichnis. Mit ```/``` können mehrere Ebenen an Unterverzeichnissen aneinander gereiht werden. z.B.: + + cd ros_ws/src/resqbots_drive_interface/ + +Der Verzeichnisname ```..``` wechselt ein Verzeichnis nach "oben". So kommt man mit + + cd .. + +wieder in das Verzeichnis ```ros_ws/src/``` und mit + + cd ../.. +wäre man im Verzeichnis ```ros_ws``` + +Der Befehl ```cd``` ohne Verzeichnisnamen führt immer in das Standardverzeichnis zurück, egal wo man vorher war. + +Das ```~``` Symbol ist ein Platzhalter für den "standard" Arbeitsbereich. Wenn man also beispielsweise im aus dem Verzeichnis ```lidar_ws/src``` in das Verzeichnis ```moveit2_ws/src``` echseln will, gelingt das mit: + + cd ~/moveit2_ws/src + +### sudo +```sudo``` steht kurz für **super user do** und entspricht dem "Als Administrator ausführen" bei Windows. Viele Befehle können nur mit dem Vorsatz ```sudo``` ausgeführt werden. Auch geschützte Dateien können nur mit ```sudo``` verändert werden. + +### apt install +```apt install ``` quasi ausschließlich mit ```sudo``` gemeinsam verwendet installiert das gewünschte Paket. + + sudo apt install hollywood + +installiert das hollywood Paket. (Ein netter Scherz, wenn man unwissende beeindrucken will.) + +### mkdir +```mkdir ``` erstellt das gewünschte Verzeichnis. + + mkdir Test + +erstellt das Verzeichnis ```Test``` + +Der zusatz ```-p``` sorgt dafür, dass alle Übergeordneten Verzeichnisse unverändert bleiben. Mit ```-p``` können auch Unterverzeichnisse in einem Befehl mit-genereirt werden. + + mkdir -p ros_ws/src + +erstellt das Verzeichnis ```src``` im Verzeichnis ```ros_ws```. Falls das Verzeichnis ```ros_ws``` nicht existiert, wird es ebenfalls erstellt. + +### rm +```rm ``` wird eigentlich nur mit ```sudo``` davor verwendet. ```sudo rm ``` löscht die benannte Datei. +Mit dem zusatz ```-r``` können auch ganze Verzeichnisse gelöscht werden. + + sudo rm -r ros_ws + +löscht den oben erstellten ```ros_ws``` und **alle Unterverzeichnisse** + +### nano +```nano``` ist der Texteditor von Ubuntu. Damit können nahezu alle schreibbaren Dateiformate göffnet und bearbeitet werden. Für schreibgeschützte Dateien musst ```sudo``` vorgesetzt werden. +Mit ```nano ``` wird die benannte Datei geöffnet, oder, falls sie nicht existiert, erstellt. Mit ```sudo nano``` erstellte Dateien sind für "normale" User schreibgeschützt und können nur mit ```sudo``` bearbeitet werden. + + sudo nano README.txt + +erstellt z.B. eine schreibgeschützte ```README.txt```. + +### Tab +Mit der ```Tab``` Taste können befehle automatisch vervollstöndigt werden. +Mit einem doppelten ```Tab``` werden alle möglichen Optionen angezeigt. + +### ssh +```ssh user@host``` stellt eine remote Verbindung zum gewählten Gerät her und loggt sich als der genannte User ein. Der **Host** kann dabei druch die **IP-Adresse** oder den **Gerätenamen** mit dem zusatz ```.local``` angegeben werden. + + ssh resqbots@q-t-pi.local + +loggt sich z.B. als user **resqbots** auf unserem RaspberryPi namen **Q-T-Pi** ein. +Will man von einem Gerät aus öfter auf das gleiche andere zugreifen, sollte man mit + + ssh-keygen + +ein **ssh public key** erstellt werden und dann mit + + ssh-copy-id user@host + +auf das Gerät kopiert werden, dass man per ssh ansteuern will. + +### ros2 run & ros2 launch +```ros2``` ist ähnlich wie ```sudo``` eine Vorsilbe, die der Shell sagt, dass sie das Programm mit der ROS2 Umgebung ausführen soll. + +```run``` und ```launch``` sind zwei varianten programme in ROS zu starten. ```run``` startet das Programm in seiner einfachsten Form. ```launch``` startet das **launch file** des Packages und kann oft mit einer vielzahl von Optionen versehen werden. + + ros2 run resqbots_drive_interface drive_interface + +startet z.B. unser drive_interface. Das zweite ```drive_interface``` ist die Startoption, die wir einfach nicht sehr kreativ benannt haben. + + ros2 launch tele_op operator.launch.py + +startet unser ```tele_op``` programm und die ```joy_node```. Die option ```operator.launch.py``` sagt dem Package, welche Nodes gestartet werden sollen. + +Die meisten launch Befehlen enden auf ```.launch``` und ```.py``` für **Python** oder ```.cpp``` für **C++**. + +### andere ros2 Befehle + +```ros2 node list``` -> Liste aktiver ROS Nodes + +```ros2 topic list``` -> Liste aktiver ROS Topics + +```ros2 topic echo``` -> Zeigt angegebenes Topic an + +```ros2 service list``` -> Liste verfügbarer ROS Services + +### ./ +```./``` führt die gewählte Datei als **Shell-Skript** aus, falls das möglich ist. In einem Skript können z.B. mehrere Befehle aneinander gereiht sein, oder Befehle mit vielen Optionen ausgeführt werden. + +  + +### Nützliche Programme + +```network-manager``` -> Netzwerk-Management + +```net-tools``` -> Netzwerkadapter + +```iperf3``` -> Netzwerkgeschwindigkeit + +```nmap``` -> Geräte im Netzwerk finden + +  + +## 3. ROS2 Installation + +Wir verwenden auf unseren Rechnern ```ros2 humble```. Auf dem Raspberry Pi 5 kann leider nur ```ros2 jazzy``` per ```apt``` installiert werden, daher kommt dort die andere Distro zum Einsatz. Bisher haben wir noch keine Kompatibilitätsprobleme entdekt, sie können aber auftreten. + +Dieser Abschnitt folgt der Installationsanleitung der ```ros2 humble``` Dokumentation + +### Locale einrichten: + sudo apt update && sudo apt install locales + sudo locale-gen en_US en_US.UTF-8 + sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 + export LANG=en_US.UTF-8 + +### ROS2 Repo einrichten: + sudo apt install software-properties-common + sudo add-apt-repository universe + +### ROS2 GPG key einrichten: + sudo apt update && sudo apt install curl -y + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + +### Repo zur source-Liste hinzufügen: + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && + echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + +### dev-tools installieren: + sudo apt update && sudo apt install ros-dev-tools + +### ROS installieren: + sudo apt update && sudo apt upgrade -y + sudo apt install ros-humble-desktop + +### ROS einrichten: +Alle Packages in Ros müssen **gesourced** werden, damit sie von der Shell gestartet werden können. +Um ein Package schnell in der aktuellen Shell zu sourcen kann der Befehl ```source $package_ws$/install/setup.bash``` verwendet werden. Wobei ```$package_ws$``` durch den Pfad zum Ordner, in dem der ```colcon-build``` Befehl ausgeführt wurde, ersetzt werden muss. (z.B. ~/ros_ws) +Falls man den ```colcon-build``` Befehl im aktuellen Ordner verwendet hat, reicht ```source install/setup.bash```. + +Um ein Package permanent zu sourcen muss der Befehlt in die **~/.bashrc** Datei geschrieben werden. Das ist eine Setup Datei, die der Shell sagt, was sie vor dem Start alles machen muss. (z.B. ROS sourcen, oder die Hintergrundfarbe ändern.) + + echo "source /opt/ros/humble/setup.bash" >> ~/.bashrc + +Die **DOMAIN_ID** sagt ROS welche Geräte in deinem Netzwerk zur gleichen Gruppe gehören. Sie ist per Default auf **0**, kann aber verändert werden. Wir haben sie aus Spaß und zur Sicherheit auf **17** gelegt. +Auch das muss in der Shell eingestellt werden: + + echo "export ROS_DOMAIN_ID=17" >> ~/.bashrc + +**rosdep** ist ein Verzeichnis in dem viele Packages über alle aktiven ROS Distros hinterlegt sind. Manchmal hilft es, das **rosdep** zur Verfügung zu haben. + + sudo rosdep init && rosdep update + +Zuletzt sollte ein **Workspace** erstellt werden, in dem an eigenen Packages gearbeitet werden kann: + + cd && mkdir -p ros_ws/src + +Grundsätzlich werden ROS Packages, die nicht einfach per ```sudo apt install``` installiert werden können in **Workspaces** gespeichert und gebuildet, damit das Dateimanagement vereinfacht wird. Die Workspaces sinnvoll zu benennen ist dabei von Vorteil. + +  + +## 4. ROS Packages + +### Package Liste + +**Fernsteuerung** +```joy``` -> liest Controllerdaten aus +```lotti_teleop``` -> wandelt Controllerdaten in Bewegungsbefehle um +```ros2_control``` und ```ros2_controller``` -> Motoren ansteuern und Feedback einholen +```robot_state_publisher``` -> zeigt Position und Lage des Roboters an +```lotti_control``` -> ros2_control Package für den "Lotti" Roboter +```lotti_flipper_controller``` -> Controller für Flipper + +**Kameras** +```camera_ros``` -> USB Kamera Interface + +**Ton** +```audio_common``` -> Micro und Lautsprecher + +**LiDAR** +[```Fast_LIO```](https://github.com/hku-mars/FAST_LIO) -> LiDAR Mapping +```PCL``` -> support für ```Fast_LIO``` +```Eigen``` -> support für ```Fast_LIO``` +[```Livox_SDK2```](https://github.com/Livox-SDK/Livox-SDK)-> LiDAR Interface +[```livox_ros_driver2```](https://github.com/Livox-SDK/livox_ros_driver2) -> LiDAR Interface +```nav2_map_server``` -> speichert LiDAR Karten + +**Anzeige** +```rviz2``` -> LiDAR Karte und robot_state +```rqt_image_view``` -> zeigt Kamerabilder an + +  + +## Packages installieren und einrichten + +[Steuerung](#steuerung) +[Kameras](#webcams) +[Ton](#audio_common) +[LiDAR](#lidar-livox-mid-360) + +### audio_common +Dieses Setup ermöglicht die Audio-Kommunikation über ROS 2 Humble zwischen einem Laptop und einem Raspberry Pi – in beide Richtungen: +Laptop → Raspberry Pi (Audioaufnahme am Laptop, Wiedergabe am Pi) +Raspberry Pi → Laptop (Audioaufnahme am Pi, Wiedergabe am Laptop) + +**Installation: Audio-Tools und Dev-Packages** + + sudo apt install -y + libasound2-dev + gstreamer1.0-plugins-base + libgstreamer1.0-dev + liborc-0.4-dev + libdw-dev libelf-dev libunwind-dev + espeak alsa-utils pavucontrol + +**ROS2 Workspace einrichten - auf BEIDEN Geräten!** + + mkdir -p ~/ros2_audio_ws/src + cd ~/ros2_audio_ws/src + git clone -b ros2 https://github.com/ros-drivers/audio_common.git + +**Abhängigkeiten & Workspace bauen** + + cd ~/ros2_audio_ws + rosdep install --from-paths src --ignore-src -r -y + colcon build --symlink-install + +**Kommunikation Raspberry Pi → Laptop** + +**Raspberry Pi (Sender)** + + export AUDIODEV=plughw:1,0 + source ~/ros2_audio_ws/install/setup.bash + ros2 run audio_capture audio_capture_node --ros-args -r __node:=capture_pi + +**Laptop (Empfänger)** + + source ~/ros2_audio_ws/install/setup.bash + ros2 run audio_play audio_play_node --ros-args -r __node:=play_laptop + +**Verifikation & Tests** + +**Verbindung prüfen (z. B. auf dem Pi):** + + ros2 topic info /audio + +**Erwartete Ausgabe:** + + Type: audio_common_msgs/msg/AudioData + Publisher count: 1 + Subscription count: 1 + +**Live-Daten anzeigen:** + + ros2 topic echo /audio + +**Testausgabe senden (z. B. am Laptop):** + + espeak "Hallo Raspberry" --stdout | aplay + + + +  + +## LiDAR: Livox MID 360 +Wir arbeiten mit dem **Livox MID 360** LiDAR. Um diesen nutzen zu können müssen auf dem Gerät, das die Daten vom LiDAR auslesen soll die Packages ```Livox_SDK2``` und ```livox_ros_driver2``` installiert sein. +Um die Daten vom LiDAR zu einer Karte zu verarbeiten, verwenden wir ```Fast_LIO```. Das wiederum benötigt ```Eigen3``` und ```PCL``` um zu funktionieren. + +Vor der Installation sollte ein **Workspace** für die Livox Packages erstellt werden: + + cd && mkdir -p livox_ws/src + + +### Livox_SDK2 +Das GitHub Repo der **SDK** in den **Workspaca** kopieren + + cd ~/livox_ws/src + git clone https://github.com/Livox-SDK/Livox-SDK2.git + +Da die **SDK** ursprünglich für frühere ROS Versionen entwickelt wurde müssen vor dem builden noch Änderungen vorgenommen werden. Dazu wird die Zeile ```#include ``` in den Bereichen mit den anderen ```#include``` Zeilen in den Dateien ```sdk_core/comm/define.h``` und ```sdk_core/logger_handler/file_manager.h``` eingefügt: + + cd Livox-SDK2 + nano sdk_core/comm/define.h + nano sdk_core/logger_handler/file_manager.h + +Danach ist das Package bereit für den build-Prozess: + + mkdir build && cd build + cmake .. + make -j + +Nach die Umsetzung des Befehls ```make -j``` dauert extrem lang und beim RaspberryPi hängt sich wahrscheinlich die ssh Verbindung auf. Nicht wundernn, einfach das Terminal schließen und nach ca. 15 Minuten neu verbinden und weiter machen. + +**Fals Verbindung abgebrochen** + +ssh aufbauen, dann + + cd livox_ws/src/Livox-SDK2/build + +**weiter builden** + + sudo make install + +Auch der build-Prozess dauer ewig, nicht wundern. ```Livox_SDK2``` ist nur ein support Package für ```livox_ros_driver2``` und muss nicht gesourced werden. + + +### livox_ros_driver2 +Das GitHup Repo in den **Workspace** kopieren + + cd ~/livox_ws/src + git clone https://github.com/Livox-SDK/livox_ros_driver2.git + +und dann builden + + cd livox_ros_driver2 + ./build.sh humble + +Der Parameter ```humble``` funktioniert auch bei humble, das Package ist einfach etwas älter. + +Nach dem erfolgreichen Builden das Package sourcen: + + source ~/livox_ws/install/setup.bash + echo "source ~/livox_ws/install/setup.bash" >> ~/.bashrc + + +### PCL +PCL ist eine Support-Suite, die viele Mathematische Prozesse im Bezug auf Punktewolken übernimmt. +Sie ist einfach zu installieren: + + sudo apt update + sudo apt install pcl-* + sudo apt install libpc-dev libpcl-ros-dev + +### Eigen3 +Eigen ist eine Sammlung an Header-Files, die den build Prozess anderer Packages unterstützen kann. Sie wird benötigt um ```Fast_LIO``` builden zu können. + +Für Eigen sollte ein extra **Workspace** erstellt werden, da es sonst zu ungewollten interaktionen mit anderen Packages kommen könnte. Der restliche Installationsprozess läuft wie immer ab. + + git clone https://gitlab.com/libeigen/eigen.git + cd eigen + mkdir build && cd build + cmake .. + make -j + sudo make install + +Auch hier ist ein **sourcen** nicht nötig. + +### Fast_LIO +Zu guter Letzt kann endlich ```Fast_LIO``` installiert werden. + +```Fast_LIO``` ist ein Package, das LiDAR Daten zu einer Karte zusammenfügen kann, ohne dafür **Odometry** Daten zu benötigen, indem es ähnlich dem Menschen "versteht" , dass sich Wände nicht bewegen, sonder der LiDAR selbst. (Nur mit deutlich mehr Mathe dahinter.) + +Auch für ```Fast_LIO``` wird ein eigener **Workspace** erstellt, das das Package wieder lang zum builden braucht und nicht versehentlich neu gebuildet werden sollte, wenn man nur ein eigenes Package testen will. + + cd && mkdir -p fast_lio_ws/src + cd fast_lio_ws/src + git clone https://github.com/Ericsii/FAST_LIO_ROS2.git --recursive + cd .. + rosdep install --from-paths src --ignore-src -y + +Nachdem das GitHub Repo in den **Workspace** kopiert und durch ```rosdep install``` erweitert wurde, muss noch die ```CMakeLists.txt``` Datei überarbeitet werden um mit der neuen ROS Version zu funktionieren. + + nano src/FAST_LIO_ROS2/CMakeLists.txt + +Und an allen Stellen das **c++14** und **c++17** durch **c++20** ersetzen. + +Danach kann das Package mit ```colcon``` gebaut und im Anschluss gesourced werden. + + colcon build --symlink-install + source install/setup.bash + echo "source ~/fast_lio_ws/install/setup.bash" >> ~/.bashrc + +Falls das Package auf einem Gerät installiert wurde, das selbst nicht live die erstellte Karte anzeigen soll muss noch die **launch-Datei** angepasst werden. + + nano install/fast_lio/share/fast_lio/launch/mapping.launch.py + +Die Zeile ```ld.add_action(rviz_node)``` mit **#** auskommentieren. + +### Nav2_map_server +```Nav2``` ist eine Package Suite für die Roboternavigation. Das Subsystem ```nav2_map_server``` verwenden wir, um die in Fast_LIO erstellten Karten zu speichern. + +**Installation:** + + sudo apt update + sudo apt install ros-humble-nav2-map-server + +**Verwendung:** + +Karte speichern mit + + ros2 launch nav2_map_server map_saver.launch + +**|unvollständig|** + + +### LiDAR Einrichten +Um den Lidar verwenden zu können müssen noch ein paar Schritte erledigt werden. + +Die ```livox_ros_driver2``` kann nur mit **statischen IP Adressen** arbeiten. Daher muss im Gerät, das die LiDAR Daten auslesen soll, **DHCP** ausgeschaltet werden. Mit + + cd /etc/netplan/ + ls + +werden alle Dateien im Verzeichnis ```netplan``` angezeigt. Normalerweise ist es nur eine, die ```50-cloud-init.yaml``` oder so ähnlich heißt. Diese ```.yaml``` Dateien sind schreibgeschützt, müssen also mit ```sudo``` geöffnet werden. + + sudo nano + +Das Terminal sollte nun ca. so aussehen: + + network: + wifis: + wlan0: + dhcp4: true + + +Unter dem Existierenden Abschnitt für ```wifis``` den folgenden Abschnitt einfügen: + + ethernets: + eth0: + dhcp4: false + addresses: + - 192.168.1.50/24 + optional: true + +Nach dem Speichern und Verlassen der Datei müssen die Änderungen übernommen werden: + + sudo netplan apply + +Jetzt hat das Gerät eine **statische IP** von 192.168.1.50 im **Ethernet**. Das Gerät kann jetzt nicht mehr über Ethernet angesteuert werden. Wird das benötigt, einfach das ```dhcp4: false``` durch ```dhcp4: true``` ersetzen. + + + +Jetzt muss in der **Konfig-Datei** die **IP Adresse** festgehalten werden. +Der Befehlt + + nano livox_ws/install/livox_ros_driver2/share/livox_ros_driver2/config/MID360_config.json + +zeigt die ```MID360_config.json``` Datei. Sie sieht nach der ersten Installation wie folgt aus: + + { + "lidar_summary_info" : { + "lidar_type": 8 + }, + "MID360": { + "lidar_net_info" : { + "cmd_data_port": 56100, + "push_msg_port": 56200, + "point_data_port": 56300, + "imu_data_port": 56400, + "log_data_port": 56500 + }, + "host_net_info" : { + "cmd_data_ip" : "192.168.1.5", + "cmd_data_port": 56101, + "push_msg_ip": "192.168.1.5", + "push_msg_port": 56201, + "point_data_ip": "192.168.1.5", + "point_data_port": 56301, + "imu_data_ip" : "192.168.1.5", + "imu_data_port": 56401, + "log_data_ip" : "", + "log_data_port": 56501 + } + }, + "lidar_configs" : [ + { + "ip" : "192.168.1.12", + "pcl_data_type" : 1, + "pattern_mode" : 0, + "extrinsic_parameter" : { + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "x": 0, + "y": 0, + "z": 0 + } + } + ] + } + +Im Abschnitt ```"MID360":``` überall die **IP Adresse** ```192.168.1.5``` durch die ```192.168.1.50``` ersetzen. + +Im Abschnitt ```"lidar_configs" :``` kann die **IP Adresse** des LiDARS eingestellt werden. Um diese zu erfahren, den LiDAR mit einem Netzwerk verbinden, einen PC mit dem gleichen Netzwerk verbinden und + + sudo apt update && sudo apt install nmap + ip a #zeigt deine IP Adresse + nmap # nur die letzte Zahl ersetzen durch 0/24 + +In der Liste sollte irgendwo der LiDAR auftauchen. Die **Default IP** unseres LiDARs ist ```192.168.1.196```. + + +### Lidar Optionen +In der Datei ```*/src/FAST_LIO_ROS2/config/mid360.yaml``` können Einstellungen für den LiDAR Betrieb vorgenommen werden. ```*``` steht für die übergeordneten Verzeichnisse. In unserem Fall wahrscheinlich ```~/fast_lio_ws``` + + nano ~/fast_lio_ws/src/FAST_LIO_ROS2/config/mid360.yaml + +Gibt folgendes aus: + + /**: + ros__parameters: + feature_extract_enable: false + point_filter_num: 3 + max_iteration: 3 + filter_size_surf: 0.5 + filter_size_map: 0.5 + cube_side_length: 1000.0 + runtime_pos_log_enable: false + map_file_path: "./test.pcd" + + common: + lid_topic: "/livox/lidar" + imu_topic: "/livox/imu" + time_sync_en: false # ONLY turn on when external time synchronization is really > + time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other al> + # This param will take effect no matter what time_sync_en is> + + preprocess: + lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ou> + scan_line: 4 + blind: 0.5 + timestamp_unit: 3 + scan_rate: 10 + + mapping: + acc_cov: 0.1 + gyr_cov: 0.1 + b_acc_cov: 0.0001 + b_gyr_cov: 0.0001 + fov_degree: 360.0 + det_range: 100.0 + extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic + extrinsic_T: [ -0.011, -0.02329, 0.04412 ] + extrinsic_R: [ 1., 0., 0., + 0., 1., 0., + 0., 0., 1.] + + publish: + path_en: true # true: publish Path + effect_map_en: false # true: publish Effects + map_en: true # true: publish Map cloud + scan_publish_en: true # false: close all the point cloud output + dense_publish_en: false # false: low down the points number in a global-frame point> + scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame + + pcd_save: + pcd_save_en: true + interval: -1 # how many LiDAR frames saved in each pcd file; + # -1 : all frames will be saved in ONE pcd file, may lead to> + + + +Bei ```map_file_path:``` den gewünschten Pfad + Dateinamen eingeben z.B. ```"~/maps/latest_map.pcd"``` + +```scan_rate:``` kann auf 10, 30, 50 oder 100 gesetzt werden und steht für die Abtastrate des LiDAR. **Vorsicht:** je höher die ```scan_rate``` desto mehr Rechenleistung wird für die Karte benötigt und desto schneller füllt sich der Arbeitsspeicher. + + +  + +## Webcams +Wir verwenden das ```camera_ros``` Package für unsere USB Kameras. + +### Installation +Die Installation ist ganz einfach: + + sudo apt update && sudo apt upgrade + sudo apt install ros-humble-camera-ros + +### Einstellungen + + + +  + +## Steuerung + +### Vorbereitung. + +**Zu installierende Programme:** +```robot_state_publisher``` -> published Position und Lage des Roboters basierend auf URDF-File. +```joint_state_publisher_gui``` -> lässt alle Gelenke manuel bewegen. +```xacro``` -> vereinfacht Erstellen von URDF-Files + + sudo apt install ros-humble-robot-state-publisher + sudo apt install ros-humble-joint-state-publisher-gui + sudo apt install ros-humble-xacro + +**URDF** + +Das ```.urdf``` File enthält Informationen über alle Bauteile und Gelenke des Roboters. Zum Erstellen eines einfachen ```.urdf``` Files am besten [diesem](https://articulatedrobotics.xyz/tutorials/ready-for-ros/urdf/) Tutorial folgen. + +Ein URDF kann auch aus CAD Dateien exportiert werden. Für SolidWorks einfach [hier](https://github.com/ros/solidworks_urdf_exporter) das Plugin installieren und dem im GitHub verlinkten Tutorial folgen. + +Falls das ```.urdf``` File mit ```xacro``` erstellt wurde, muss es erst mit + + xacro file_name.urdf.xacro > file_name.urdf + +zu einem normalen ```.urdf``` File kompiliert werden. Danach 2 Terminals öffnen. + + 1. ros2 run robot_state_publisher robot_state_publisher file_name.urdf + 2. ros2 run joint_state_publisher_gui joint_state_publisher_gui + +```1.``` publisht die Position und Lage des Robots, ```2.``` published das ```/tf``` Topic und ermöglicht, die Gelenke des Roboters durch Schieber zu bewegen. + + +### ros2_control und MoveIt2 +Für die Steuerung des Roboters verwenden wir ```ros2_control```. Für die inverse Kinematik und Motorkoordinierung des Arms kommt ```moveit2``` zum Einsatz. + +**Installation:** + +```ros2_control``` ist ein Standard-Package in ROS2 und somit einfach zu installieren: + + sudo apt install ros-humble-ros2-control ros-humble-ros2-controller + +```moveit2``` ist etwas aufwändiger: +Vorbereitung: + + sudo apt install python3-rosdep #rosdep sollte bereits installiert sein + sudo rosdep init #rosdep sollte bereits initiallisiert sein + rosdep update #vor der Verwendung alles auf den neusten Stand bringen + sudo apt update + sudo apt dist-upgrade + +Colcon ist bereits in der ROS installation enthalten, aber die Funktion ```--mixin-release``` nicht. Deshalb wird sie installiert: + + sudo apt install python3-colcon-common-extensions + sudo apt install python3-colcon-mixin + colcon mixin add default https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml + colcon mixin update default + sudo apt install python3-vcstool + +Als nächstes wird ein Workspace erstellt, damit MoveIt2 nicht versehentlich neu kompiliert wird, wenn wir an anderen Projekten arbeiten: + + mkdir -p ~/moveit2_ws/src + +Nun den Tutorial-Ordner aus dem GitHub Repo installieren: + + cd ~/moveit2_ws/src + git clone --branch humble https://github.com/ros-planning/moveit2_tutorials + vcs import < moveit2_tutorials/moveit2_tutorials.repos + sudo apt update && rosdep install -r --from-paths . --ignore-src --rosdistro $ROS_DISTRO -y + cd ~/moveit2_ws + +Das Kompilieren von MoveIt2 dauer extrem lang und ist absurd Resourcenaufwendig. Vor dem Start alle anderen Anwendungen und Prozesse schließen und externe Bildschirme abstecken. Der Prozess wird ca. 30 Minuten dauern, wenn alles gut geht. Evtl. hängt sich der Computer zwischendurch auf, in dem Fall einfach neu Starten und den ```colcon``` Befehl wiederholen. Der Fortschritt bis zum Aufhängen bleibt bestehen. Man kann das also einfach so oft wiederholen, bis das Package fertig kompiliert ist. + + colcon build --mixin-release --symlink-install --executor sequential + +Wenn der Prozess erfolgreich beendet wurde, das Package sourcen und in der ```.bashrc``` integrieren. + + source install/setup.bash + echo "source ~/moveit2_ws/install/setup.bash" >> ~/.bashrc + + +**Modifikationen** +Wir verwenden das MoveIt2 Modul ```moveit_servo``` um unseren Arm mit dem X-Box Controller zu steuern. Um das Modul mit unsererm ```lotti_teleop``` Package kombinieren zu können, müssen ein paar Modifikationen vorgenommen werden. + +  + +## 5. Arduino Packages diff --git a/Roadmap ResQ Bots.pptx b/Roadmap ResQ Bots.pptx deleted file mode 100644 index 034f4e0..0000000 Binary files a/Roadmap ResQ Bots.pptx and /dev/null differ diff --git a/botlaunch/launch/operator.launch.py b/botlaunch/launch/operator.launch.py deleted file mode 100644 index 7a3165e..0000000 --- a/botlaunch/launch/operator.launch.py +++ /dev/null @@ -1,64 +0,0 @@ -import os -from launch import LaunchDescription -from launch_ros.actions import Node -from launch.substitutions import LaunchConfiguration -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from ament_index_python import get_package_share_directory - -def generate_launch_description(): - - #get directories - chain_package = get_package_share_directory ('chain_controller') - - joy_node = Node( - package='joy', - namespace='Controller', - executable='joy_node', - name='Controller' - ) - - chain_controller_node = IncludeLaunchDescription( - os.path.join(chain_package, 'launch', 'default_launch.py'), - ) - - uncompress_cam1 = Node( - package='image_transport', - executable='republish', - arguments= [ - 'compressed', - 'raw', - ], - remappings=[ - ('in/compressed', 'usb_cam_1/image_raw/compressed'), - ('out', 'usb_cam_1/image_raw/uncompressed') - ] - ) - - uncompress_cam2 = Node( - package='image_transport', - executable='republish', - arguments= [ - 'compressed', - 'raw', - ], - remappings=[ - ('in/compressed', 'usb_cam_2/image_raw/compressed'), - ('out', 'usb_cam_2/image_raw/uncompressed') - ] - ) - - web_video_server_node= Node( - package='web_video_server', - namespace='web_video_server', - executable='web_video_server', - name='Video_Server' - ) - - return LaunchDescription([ - joy_node, - chain_controller_node, - uncompress_cam1, - uncompress_cam2, - web_video_server_node - ]) \ No newline at end of file diff --git a/botlaunch/launch/robot.launch.py b/botlaunch/launch/robot.launch.py deleted file mode 100644 index 5aaba63..0000000 --- a/botlaunch/launch/robot.launch.py +++ /dev/null @@ -1,72 +0,0 @@ -import os -from launch import LaunchDescription -from launch_ros.actions import Node -from launch.substitutions import LaunchConfiguration -from launch.actions import DeclareLaunchArgument -from launch.actions import IncludeLaunchDescription -from ament_index_python import get_package_share_directory - -def generate_launch_description(): - - #get directories - drive_package = get_package_share_directory('resqbot_drive_interface') - flipper_package = get_package_share_directory('resqbot_flipper_interface') - -# usb_cam_1_config_file_path = LaunchConfiguration('usb_cam_1_config_file_path') -# declare_usb_cam_1_config_file_path = DeclareLaunchArgument( -# 'usb_cam_1_config_file_path', -# default_value='~/dev_ws/src/web_video_server/cam1.yaml', -# ) - - drive_interface_node = IncludeLaunchDescription( - os.path.join(drive_package, 'launch', 'default_launch.py'), - ) - - flipper_interface_node = IncludeLaunchDescription( - os.path.join(flipper_package, 'launch', 'default_launch.py'), - ) - - usb_cam_1_node = Node( - package='usb_cam', - namespace='usb_cam_1', - executable='usb_cam_node_exe', - name='usb_cam_1', - output= 'screen', - parameters=[{ - 'video_device': "/dev/video0", - 'framerate': 10.0, - 'io_method': "mmap", - 'frame_id': "cam1", - 'pixel_format': "yuyv2rgb", - 'color_format': "yuyv2rgb", - 'image_width': 320, - 'image_height': 240, - 'camera_name': "cam1" - }] - ) - - usb_cam_2_node = Node( - package='usb_cam', - namespace='usb_cam_2', - executable='usb_cam_node_exe', - name='usb_cam_2', - output= 'screen', - parameters=[{ - 'video_device': "/dev/video2", - 'framerate': 10.0, - 'io_method': "mmap", - 'frame_id': "cam2", - 'pixel_format': "yuyv2rgb", - 'color_format': "yuyv2rgb", - 'image_width': 320, - 'image_height': 240, - 'camera_name': "cam2" - }] - ) - - return LaunchDescription([ - drive_interface_node, - flipper_interface_node, - usb_cam_1_node, - usb_cam_2_node - ]) \ No newline at end of file diff --git a/botlaunch/setup.cfg b/botlaunch/setup.cfg deleted file mode 100644 index cfe922d..0000000 --- a/botlaunch/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/botlaunch -[install] -install_scripts=$base/lib/botlaunch diff --git a/chain_controller/chain_controller/chain_controller.py b/chain_controller/chain_controller/chain_controller.py deleted file mode 100644 index 286aa56..0000000 --- a/chain_controller/chain_controller/chain_controller.py +++ /dev/null @@ -1,299 +0,0 @@ -import rclpy -import time -from rclpy.node import Node -import math -import numpy - -from sensor_msgs.msg import Joy -from std_msgs.msg import Float32 -from std_msgs.msg import Int16 -from std_msgs.msg import Bool -from rclpy import qos -from threading import Lock - -# Global Defines -------------------------------------------------------------- -#DRIVE_INTERFACE_STS_INIT = 0 -#DRIVE_INTERFACE_STS_RUN = 1 - -xAxes = 0 -yAxes = 1 - -x_button = 2 -y_button = 3 -a_button = 0 -b_button = 1 -lb_button = 4 -rb_button = 5 - -#max_motor_speed = 4000.0 -#transmission = 111*45/24 -#max_speed = float(max_motor_speed / transmission) -PI=3.1415926535897 - -# Class ----------------------------------------------------------------------- -class chainController(Node): - - def __init__(self): - #Entrypoint of the class - super().__init__('chain_controller') - - #define variables - self.__velocity = Float32() - self.__alpha = Float32() - - self.__cmd_speed_x = float(0) - self.__cmd_speed_x_lock = Lock() - self.__cmd_speed_y = float(0) - self.__cmd_speed_y_lock = Lock() - self.flipper_mode = int(0) - self._speed = float(0) - - self.__button_a = int(0) - self.__button_a_lock = Lock() - self.__button_b = int(0) - self.__button_b_lock = Lock() - self.__button_x = int(0) - self.__button_x_lock = Lock() - self.__button_y = int(0) - self.__button_y_lock = Lock() - self.__button_lb = int(0) - self.__button_lb_lock = Lock() - self.__button_rb = int(0) - self.__button_rb_lock = Lock() - - self.__flipper_frontLeft_cmd = Int16() - self.__flipper_frontRight_cmd = Int16() - self.__flipper_rearLeft_cmd = Int16() - self.__flipper_rearRight_cmd = Int16() - - - self.__time_last_joy_msg = 0.0 - self._first_joy_msg_received = Bool() - - self.__joy_enabled = False - self.__joy_enabled_old = False - - # Status see timer callback for description -# self.__state = DRIVE_INTERFACE_STS_INIT - - #Init class ->create subscriber, create timer - self.__readParams() - self.__createSubscribers() - self.__createPublishers() - self.__createTimer() - - def __readParams(self): - #declare parameters - self.declare_parameter('Publish_rate', 10) #[Hz] - self.declare_parameter('Joy_timeout', 1) #[sec] - - #read parameters - self.__Publish_rate = rclpy.parameter.Parameter( - 'Publish_rate', - rclpy.Parameter.Type.DOUBLE, - 10.0 - ) - self.__Joy_timeout = 1.0 - - - def __checkCMDOutputEnable(self): - - # ----- Timout error check ----- - # If the time difference between the last recived flipper msg and now is greater then the timeout, DISABLE the motor rpm output - self.__time_since_last_joy_msg = 0.0 - - if (self.__time_last_joy_msg != 0.0 and self.__Joy_timeout != 0.0): - # Calculate the time difference - self.__time_since_last_joy_msg = time.time() - self.__time_last_joy_msg - - # If there was a joy msg before, the flipper output is in ENABLED status but the time since the last joy msg was received - # is greater then the timout time, DISABLE the flipper output and print a msg for the user that there was a timeout. - if (self.__joy_enabled == True and self.__time_since_last_joy_msg > self.__Joy_timeout): - self._joy_enabled = False - self.get_logger().error("Joy msg timeout") - else: - self.__joy_enabled = True - - # Print a message to show the current flipper output status. - if self.__joy_enabled != self.__joy_enabled_old: - if (self.__joy_enabled == True and self.__joy_enabled_old == False): - self.get_logger(), "Chain command: ENABLED" - else: - if (self.__joy_enabled == False and self.__joy_enabled_old == True): - self.get_logger(), "Chain command: DISABLED" - - # Set the old state to the new state - self.__joy_enabled_old = self.__joy_enabled - - - def __calcAndSendMovement(self): - - x_value = self.__cmd_speed_x - y_value = self.__cmd_speed_y - - #calculating desired velocity - self.__speed = math.sqrt((x_value * x_value) + (y_value * y_value)) - - self.__velocity.data = self.__speed - - #calculating desired angle - #avoiding division by 0 - if(y_value == 0): - self.__angle = (PI / 2) - else: - self.__angle = math.atan(x_value/y_value) - #using degrees to be humanly understandable - self.__angle = math.degrees(self.__angle) - #using absolute to solve direcional problems - self.__angle_abs = float(abs(self.__angle)) - - if(y_value < 0): - self.__angle_abs = 180 - self.__angle_abs - - if(x_value < 0): - self.__angle_abs = self.__angle_abs * (-1) - - self.__alpha.data = self.__angle_abs - - self.__velocityPub.publish(self.__velocity) - self.__angularPub.publish(self.__alpha) - - #set Flipper commands - if (self.__button_lb == 1): - self.__flipper_mode = -1 - elif (self.__button_rb == 1): - self.__flipper_mode = 1 - else: - self.__flipper_mode = 0 - - self.__flipper_frontLeft_cmd.data = int(self.__button_x * self.__flipper_mode) - self.__flipper_frontRight_cmd.data = int(self.__button_y * self.__flipper_mode) - self.__flipper_rearLeft_cmd.data = int(self.__button_a * self.__flipper_mode) - self.__flipper_rearRight_cmd.data = int(self.__button_b * self.__flipper_mode) - - #send the commands - self.__pub_flipper_frontLeft.publish(self.__flipper_frontLeft_cmd) - self.__pub_flipper_frontRight.publish(self.__flipper_frontRight_cmd) - self.__pub_flipper_rearLeft.publish(self.__flipper_rearLeft_cmd) - self.__pub_flipper_rearRight.publish(self.__flipper_rearRight_cmd) - - - - - def __timerCallback(self): - self.__checkCMDOutputEnable() - self.__calcAndSendMovement() - - - - def __joyCallback(self, msg): - self.__cmd_speed_x_lock.acquire() - self.__cmd_speed_x = msg.axes[xAxes] - self.__cmd_speed_x_lock.release() - - self.__cmd_speed_y_lock.acquire() - self.__cmd_speed_y = msg.axes[yAxes] - self.__cmd_speed_y_lock.release() - - self.__button_x_lock.acquire() - self.__button_x = msg.buttons[x_button] - self.__button_x_lock.release() - - self.__button_y_lock.acquire() - self.__button_y = msg.buttons[y_button] - self.__button_y_lock.release() - - self.__button_a_lock.acquire() - self.__button_a = msg.buttons[a_button] - self.__button_a_lock.release() - - self.__button_b_lock.acquire() - self.__button_b = msg.buttons[b_button] - self.__button_b_lock.release() - - self.__button_lb_lock.acquire() - self.__button_lb = msg.buttons[lb_button] - self.__button_lb_lock.release() - - self.__button_rb_lock.acquire() - self.__button_rb = msg.buttons[rb_button] - self.__button_rb_lock.release() - - # Check if there was a joy msgs since the node was started - if(self._first_joy_msg_received == False): - self._first_joy_msg_received = True - - - def __createSubscribers(self): - # Create subscribers - - self._joy_sub = self.create_subscription( - Joy, - 'joy', - self.__joyCallback, - 5, - ) - - def __createPublishers(self): - # Create publishers - - self.__velocityPub = self.create_publisher( - Float32, - 'movement/velocity', - 1 - ) - - self.__angularPub = self.create_publisher( - Float32, - 'movement/angle', - 1 - ) - - self.__pub_flipper_frontLeft = self.create_publisher( - Int16, - 'cmd/flipper/frontLeft', - 1 - ) - - self.__pub_flipper_frontRight = self.create_publisher( - Int16, - 'cmd/flipper/frontRight', - 1 - ) - - self.__pub_flipper_rearLeft = self.create_publisher( - Int16, - 'cmd/flipper/rearLeft', - 1 - ) - - self.__pub_flipper_rearRight = self.create_publisher( - Int16, - 'cmd/flipper/rearRight', - 1 - ) - - def __createTimer(self): - # Create timer - self._timer = self.create_timer( - 1.0 / self.__Publish_rate.value, - self.__timerCallback - ) - - -def main(args=None): - rclpy.init(args=args) - - chain_controller = chainController() - - rclpy.spin(chain_controller) - - # Destroy the node explicitly - # (optional - otherwise it will be done automatically - # when the garbage collector destroys the node object) - chain_controller.destroy_node() - rclpy.shutdown() - - -if __name__ == '__main__': - main() diff --git a/chain_controller/launch/default_launch.py b/chain_controller/launch/default_launch.py deleted file mode 100644 index 48a4b97..0000000 --- a/chain_controller/launch/default_launch.py +++ /dev/null @@ -1,27 +0,0 @@ -import os - -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription -from launch.conditions import IfCondition -from launch.substitutions import LaunchConfiguration, TextSubstitution -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch_ros.actions import Node -from launch_ros.substitutions import FindPackageShare - - -def generate_launch_description(): - - return LaunchDescription([ - Node( - package='chain_controller', - namespace='', - executable='chain_controller', - name='chain_controller', - output="screen", - emulate_tty=True, - parameters=[{ - }], - arguments=['--ros-args', '--log-level', 'info'] - ), - ]) \ No newline at end of file diff --git a/chain_controller/setup.cfg b/chain_controller/setup.cfg deleted file mode 100644 index 5983171..0000000 --- a/chain_controller/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/chain_controller -[install] -install_scripts=$base/lib/chain_controller diff --git a/control_ws/src/.vscode/settings.json b/control_ws/src/.vscode/settings.json new file mode 100644 index 0000000..35171c8 --- /dev/null +++ b/control_ws/src/.vscode/settings.json @@ -0,0 +1,108 @@ +{ + "cmake.sourceDirectory": "/home/paul/resqbot_dev/control_ws/src/lotti_control", + "files.associations": { + "*.xacro": "xml", + "*.rst": "restructuredtext", + "cctype": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "array": "cpp", + "atomic": "cpp", + "strstream": "cpp", + "bit": "cpp", + "bitset": "cpp", + "chrono": "cpp", + "compare": "cpp", + "complex": "cpp", + "concepts": "cpp", + "condition_variable": "cpp", + "cstdint": "cpp", + "deque": "cpp", + "forward_list": "cpp", + "list": "cpp", + "map": "cpp", + "set": "cpp", + "string": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "ratio": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "initializer_list": "cpp", + "iomanip": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "new": "cpp", + "numbers": "cpp", + "ostream": "cpp", + "semaphore": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "stop_token": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "cfenv": "cpp", + "cinttypes": "cpp", + "typeindex": "cpp", + "typeinfo": "cpp", + "csetjmp": "cpp", + "csignal": "cpp", + "any": "cpp", + "barrier": "cpp", + "charconv": "cpp", + "codecvt": "cpp", + "coroutine": "cpp", + "cuchar": "cpp", + "netfwd": "cpp", + "regex": "cpp", + "source_location": "cpp", + "hash_map": "cpp", + "hash_set": "cpp", + "rope": "cpp", + "slist": "cpp", + "future": "cpp", + "latch": "cpp", + "ranges": "cpp", + "scoped_allocator": "cpp", + "shared_mutex": "cpp", + "span": "cpp", + "syncstream": "cpp", + "valarray": "cpp", + "variant": "cpp" + }, + "python.autoComplete.extraPaths": [ + "/home/paul/ws_livox/install/livox_ros_driver2/local/lib/python3.10/dist-packages", + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ], + "python.analysis.extraPaths": [ + "/home/paul/ws_livox/install/livox_ros_driver2/local/lib/python3.10/dist-packages", + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ] +} \ No newline at end of file diff --git a/botlaunch/botlaunch/__init__.py b/control_ws/src/learning_tf2_py/learning_tf2_py/__init__.py similarity index 100% rename from botlaunch/botlaunch/__init__.py rename to control_ws/src/learning_tf2_py/learning_tf2_py/__init__.py diff --git a/control_ws/src/learning_tf2_py/learning_tf2_py/__pycache__/__init__.cpython-310.pyc b/control_ws/src/learning_tf2_py/learning_tf2_py/__pycache__/__init__.cpython-310.pyc new file mode 100644 index 0000000..aa77355 Binary files /dev/null and b/control_ws/src/learning_tf2_py/learning_tf2_py/__pycache__/__init__.cpython-310.pyc differ diff --git a/control_ws/src/learning_tf2_py/learning_tf2_py/__pycache__/static_turtle_tf2_broadcaster.cpython-310.pyc b/control_ws/src/learning_tf2_py/learning_tf2_py/__pycache__/static_turtle_tf2_broadcaster.cpython-310.pyc new file mode 100644 index 0000000..c7225b9 Binary files /dev/null and b/control_ws/src/learning_tf2_py/learning_tf2_py/__pycache__/static_turtle_tf2_broadcaster.cpython-310.pyc differ diff --git a/control_ws/src/learning_tf2_py/learning_tf2_py/static_turtle_tf2_broadcaster.py b/control_ws/src/learning_tf2_py/learning_tf2_py/static_turtle_tf2_broadcaster.py new file mode 100644 index 0000000..e5f3186 --- /dev/null +++ b/control_ws/src/learning_tf2_py/learning_tf2_py/static_turtle_tf2_broadcaster.py @@ -0,0 +1,104 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import math +import sys + +from geometry_msgs.msg import TransformStamped + +import numpy as np + +import rclpy +from rclpy.node import Node + +from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster + + +# This function is a stripped down version of the code in +# https://github.com/matthew-brett/transforms3d/blob/f185e866ecccb66c545559bc9f2e19cb5025e0ab/transforms3d/euler.py +# Besides simplifying it, this version also inverts the order to return x,y,z,w, which is +# the way that ROS prefers it. +def quaternion_from_euler(ai, aj, ak): + ai /= 2.0 + aj /= 2.0 + ak /= 2.0 + ci = math.cos(ai) + si = math.sin(ai) + cj = math.cos(aj) + sj = math.sin(aj) + ck = math.cos(ak) + sk = math.sin(ak) + cc = ci*ck + cs = ci*sk + sc = si*ck + ss = si*sk + + q = np.empty((4, )) + q[0] = cj*sc - sj*cs + q[1] = cj*ss + sj*cc + q[2] = cj*cs - sj*sc + q[3] = cj*cc + sj*ss + + return q + + +class StaticFramePublisher(Node): + """ + Broadcast transforms that never change. + + This example publishes transforms from `world` to a static turtle frame. + The transforms are only published once at startup, and are constant for all + time. + """ + + def __init__(self): + super().__init__('static_robot_tf') + + self.tf_static_broadcaster = StaticTransformBroadcaster(self) + + # Publish static transforms once at startup + self.make_transforms() + + def make_transforms(self): + t = TransformStamped() + + t.header.stamp = self.get_clock().now().to_msg() + t.header.frame_id = 'body' + t.child_frame_id = 'body_link' + + t.transform.translation.x = 0.0 + t.transform.translation.y = 0.0 + t.transform.translation.z = 0.0 + quat = quaternion_from_euler(0.0, 0.0, 0.0) + t.transform.rotation.x = quat[0] + t.transform.rotation.y = quat[1] + t.transform.rotation.z = quat[2] + t.transform.rotation.w = quat[3] + + self.tf_static_broadcaster.sendTransform(t) + + +def main(): + logger = rclpy.logging.get_logger('logger') + + + # pass parameters and initialize node + rclpy.init() + node = StaticFramePublisher() + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + + rclpy.shutdown() diff --git a/botlaunch/package.xml b/control_ws/src/learning_tf2_py/package.xml similarity index 75% rename from botlaunch/package.xml rename to control_ws/src/learning_tf2_py/package.xml index 2cf374b..8b5ab4a 100644 --- a/botlaunch/package.xml +++ b/control_ws/src/learning_tf2_py/package.xml @@ -1,11 +1,11 @@ - botlaunch + learning_tf2_py 0.0.0 TODO: Package description - resqbots - Apache-2.0 + paul + TODO: License declaration ament_copyright ament_flake8 diff --git a/botlaunch/resource/botlaunch b/control_ws/src/learning_tf2_py/resource/learning_tf2_py similarity index 100% rename from botlaunch/resource/botlaunch rename to control_ws/src/learning_tf2_py/resource/learning_tf2_py diff --git a/control_ws/src/learning_tf2_py/setup.cfg b/control_ws/src/learning_tf2_py/setup.cfg new file mode 100644 index 0000000..b01ce8a --- /dev/null +++ b/control_ws/src/learning_tf2_py/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/learning_tf2_py +[install] +install_scripts=$base/lib/learning_tf2_py diff --git a/chain_controller/setup.py b/control_ws/src/learning_tf2_py/setup.py similarity index 60% rename from chain_controller/setup.py rename to control_ws/src/learning_tf2_py/setup.py index 47186db..16bc9aa 100644 --- a/chain_controller/setup.py +++ b/control_ws/src/learning_tf2_py/setup.py @@ -1,29 +1,26 @@ from setuptools import find_packages, setup -import os -from glob import glob -package_name = 'chain_controller' +package_name = 'learning_tf2_py' setup( name=package_name, version='0.0.0', - packages=[package_name], + packages=find_packages(exclude=['test']), data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name, 'launch/'), glob('launch/*launch.[pxy][yma]*')), ], install_requires=['setuptools'], zip_safe=True, - maintainer='resqbots', - maintainer_email='resqbots@todo.todo', + maintainer='paul', + maintainer_email='73643665+PaulKupka@users.noreply.github.com', description='TODO: Package description', license='TODO: License declaration', tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'chain_controller = chain_controller.chain_controller:main' + 'body_tf = learning_tf2_py.static_turtle_tf2_broadcaster:main', ], }, ) diff --git a/botlaunch/test/test_copyright.py b/control_ws/src/learning_tf2_py/test/test_copyright.py similarity index 100% rename from botlaunch/test/test_copyright.py rename to control_ws/src/learning_tf2_py/test/test_copyright.py diff --git a/botlaunch/test/test_flake8.py b/control_ws/src/learning_tf2_py/test/test_flake8.py similarity index 100% rename from botlaunch/test/test_flake8.py rename to control_ws/src/learning_tf2_py/test/test_flake8.py diff --git a/botlaunch/test/test_pep257.py b/control_ws/src/learning_tf2_py/test/test_pep257.py similarity index 100% rename from botlaunch/test/test_pep257.py rename to control_ws/src/learning_tf2_py/test/test_pep257.py diff --git a/control_ws/src/lotti_control/.vscode/c_cpp_properties.json b/control_ws/src/lotti_control/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..4359fa3 --- /dev/null +++ b/control_ws/src/lotti_control/.vscode/c_cpp_properties.json @@ -0,0 +1,35 @@ +{ + "configurations": [ + { + "browse": { + "databaseFilename": "${default}", + "limitSymbolsToIncludedHeaders": false + }, + "includePath": [ + "/home/paul/resqbot_dev/control_ws/install/lotti_control/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_9/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_8/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_7/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_6/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_5/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_4/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_3/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_2/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_14/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_12/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_11/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_10/include/**", + "/home/paul/ros2_ws/install/ros2_control_demo_example_1/include/**", + "/home/paul/ws_livox/install/livox_ros_driver2/include/**", + "/opt/ros/humble/include/**", + "/usr/include/**" + ], + "name": "ROS", + "intelliSenseMode": "gcc-x64", + "compilerPath": "/usr/bin/gcc", + "cStandard": "gnu11", + "cppStandard": "c++14" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/control_ws/src/lotti_control/.vscode/settings.json b/control_ws/src/lotti_control/.vscode/settings.json new file mode 100644 index 0000000..7997bd0 --- /dev/null +++ b/control_ws/src/lotti_control/.vscode/settings.json @@ -0,0 +1,17 @@ +{ + "python.autoComplete.extraPaths": [ + "/home/paul/ws_livox/install/livox_ros_driver2/local/lib/python3.10/dist-packages", + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ], + "python.analysis.extraPaths": [ + "/home/paul/ws_livox/install/livox_ros_driver2/local/lib/python3.10/dist-packages", + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ], + "files.associations": { + "*.xacro": "xml", + "sstream": "cpp", + "string": "cpp" + } +} \ No newline at end of file diff --git a/control_ws/src/lotti_control/.vscode/tasks.json b/control_ws/src/lotti_control/.vscode/tasks.json new file mode 100644 index 0000000..08d9005 --- /dev/null +++ b/control_ws/src/lotti_control/.vscode/tasks.json @@ -0,0 +1,28 @@ +{ + "tasks": [ + { + "type": "cppbuild", + "label": "C/C++: gcc build active file", + "command": "/usr/bin/gcc", + "args": [ + "-fdiagnostics-color=always", + "-g", + "${file}", + "-o", + "${fileDirname}/${fileBasenameNoExtension}" + ], + "options": { + "cwd": "${fileDirname}" + }, + "problemMatcher": [ + "$gcc" + ], + "group": { + "kind": "build", + "isDefault": true + }, + "detail": "Task generated by Debugger." + } + ], + "version": "2.0.0" +} \ No newline at end of file diff --git a/control_ws/src/lotti_control/CMakeLists.txt b/control_ws/src/lotti_control/CMakeLists.txt new file mode 100644 index 0000000..54fa787 --- /dev/null +++ b/control_ws/src/lotti_control/CMakeLists.txt @@ -0,0 +1,115 @@ +cmake_minimum_required(VERSION 3.16) +project(lotti_control LANGUAGES CXX) + +if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra) +endif() + +# set the same behavior for windows as it is on linux +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + +# find dependencies +set(HW_IF_INCLUDE_DEPENDS + pluginlib + rcpputils + hardware_interface + rclcpp +) + +#set(CONTROLLER_INCLUDE_DEPENDS +# pluginlib +# rcpputils +# controller_interface +# realtime_tools +# sensor_msgs +#) + +# find dependencies +find_package(backward_ros REQUIRED) +find_package(ament_cmake REQUIRED) +foreach(Dependency IN ITEMS ${HW_IF_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() +#foreach(Dependency IN ITEMS ${CONTROLLER_INCLUDE_DEPENDS}) +# find_package(${Dependency} REQUIRED) +#endforeach() + +## COMPILE +#add_executable(arm_teleop lotti_control/arm_teleop.cpp) +#add_executable(chain_controller lotti_control/chain_controller.cpp) +#add_executable(flipper_controller lotti_control/flipper_controller.cpp) + + +#ament_target_dependencies( +# send_trajectory PUBLIC +# ${REF_GEN_INCLUDE_DEPENDS} +#) + +add_library( + lotti_control + SHARED + hardware/arm_interface.cpp + hardware/flipper_interface.cpp + hardware/diffbot_system.cpp +) + +target_compile_features(lotti_control PUBLIC cxx_std_17) +target_include_directories(lotti_control PUBLIC +$ +#$ +$ +) +ament_target_dependencies( + lotti_control PUBLIC + ${HW_IF_INCLUDE_DEPENDS} +# ${CONTROLLER_INCLUDE_DEPENDS} +) +target_link_libraries(lotti_control PUBLIC serial) + +# Export hardware plugins +pluginlib_export_plugin_description_file(hardware_interface lotti_control.xml) +# Export controller plugins +#pluginlib_export_plugin_description_file(controller_interface lotti_control.xml) + +# INSTALL +install( + DIRECTORY hardware/include/ + DESTINATION include/lotti_control +) +#install( +# DIRECTORY controller/include/ +# DESTINATION include/lotti_control +#) +install( + DIRECTORY description/launch description/urdf description/srdf description/meshes + DESTINATION share/lotti_control/description +) +install( + DIRECTORY description/ros2_control + DESTINATION share/lotti_control +) +install( + DIRECTORY bringup/launch bringup/config + DESTINATION share/lotti_control +) + +install(TARGETS lotti_control + EXPORT export_lotti_control + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +if(BUILD_TESTING) + find_package(ament_cmake_pytest REQUIRED) + + ament_add_pytest_test(lotti_urdf_xacro test/test_urdf_xacro.py) + ament_add_pytest_test(view_lotti_launch test/test_view_robot_launch.py) + ament_add_pytest_test(run_lotti_launch test/test_lotti_controller_launch.py) +endif() + +## EXPORTS +ament_export_targets(export_lotti_control HAS_LIBRARY_TARGET) +ament_export_dependencies(${HW_IF_INCLUDE_DEPENDS}) +#${REF_GEN_INCLUDE_DEPENDS} ${CONTROLLER_INCLUDE_DEPENDS}) +ament_package() diff --git a/control_ws/src/lotti_control/bringup/config/Lotti_controllers.yaml b/control_ws/src/lotti_control/bringup/config/Lotti_controllers.yaml new file mode 100644 index 0000000..1efe536 --- /dev/null +++ b/control_ws/src/lotti_control/bringup/config/Lotti_controllers.yaml @@ -0,0 +1,139 @@ +controller_manager: + ros__parameters: + update_rate: 100 #Hz + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + arm_controller: + type: joint_trajectory_controller/JointTrajectoryController + + flipper_controller: + type: flipper_controller/FlipperController + + chain_controller: + type: diff_drive_controller/DiffDriveController + +arm_controller: + ros__parameters: + joints: + - arm_link1_joint + - arm_link2_joint + - arm_link3_joint + - arm_link4_joint + - arm_link5_joint + - arm_link6_joint + command_interfaces: + - position + - velocity + state_interfaces: + - position + - velocity + allow_partial_joints_goal: true + open_loop_control: false + interpolate_from_desired_state: true + set_last_command_interface_value_as_state_on_activation: false + allow_nonzero_velocity_at_trajectory_end: true + constraints: + stopped_velocity_tolerance: 0.01 + goal_time: 0.05 + publish_rate: 20.0 +# gains: +# arm_link1_joint: +# p: 0.5 +# i: 0.0 +# d: 0.0 +# i_clamp: 0.0 +# ff_velocity_scale: 1.0 +# arm_link2_joint: +# p: 0.5 +# i: 0.0 +# d: 0.0 +# i_clamp: 0.0 +# ff_velocity_scale: 1.0 +# arm_link3_joint: +# p: 0.5 +# i: 0.0 +# d: 0.0 +# i_clamp: 0.0 +# ff_velocity_scale: 1.0 +# arm_link4_joint: +# p: 0.5 +# i: 0.0 +# d: 0.0 +# i_clamp: 0.0 +# ff_velocity_scale: 1.0 +# arm_link5_joint: +# p: 0.5 +# i: 0.0 +# d: 0.0 +# i_clamp: 0.0 +# ff_velocity_scale: 1.0 +# arm_link6_joint: +# p: 0.5 +# i: 0.0 +# d: 0.0 +# i_clamp: 0.0 +# ff_velocity_scale: 1.0 + + +flipper_controller: + ros__parameters: + joints: + - flipper_fr_joint + - flipper_fl_joint + - flipper_rr_joint + - flipper_rl_joint + command_interfaces: + - velocity + state_interfaces: + - position + + +chain_controller: + ros__parameters: + left_wheel_names: ["left_chain_joint"] + right_wheel_names: ["right_chain_joint"] + + wheel_separation: 0.192 + wheels_per_side: 1 + wheel_radius: 0.10 + + wheel_separation_multiplier: 1.0 + left_wheel_radius_multiplier: 1.0 + right_wheel_radius_multiplier: 1.0 + + #publish_rate: 50.0 + odom_frame_id: odom + base_frame_id: body_link + pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] + twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] + + open_loop: true + enable_odom_tf: false + + cmd_vel_timeout: 0.5 + #publish_limited_velocity: true + use_stamped_vel: false + #velocity_rolling_window_size: 10 + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear.x.has_velocity_limits: true + linear.x.has_acceleration_limits: true + linear.x.has_jerk_limits: false + linear.x.max_velocity: 23.0 + linear.x.min_velocity: -23.0 + linear.x.max_acceleration: 5.0 + linear.x.max_jerk: 0.0 + linear.x.min_jerk: 0.0 + + angular.z.has_velocity_limits: true + angular.z.has_acceleration_limits: true + angular.z.has_jerk_limits: false + angular.z.max_velocity: 1.0 + angular.z.min_velocity: -1.0 + angular.z.max_acceleration: 1.0 + angular.z.min_acceleration: -1.0 + angular.z.max_jerk: 0.0 + angular.z.min_jerk: 0.0 \ No newline at end of file diff --git a/control_ws/src/lotti_control/bringup/config/MID360_config.json b/control_ws/src/lotti_control/bringup/config/MID360_config.json new file mode 100644 index 0000000..29ef00e --- /dev/null +++ b/control_ws/src/lotti_control/bringup/config/MID360_config.json @@ -0,0 +1,42 @@ +{ + "lidar_summary_info": { + "lidar_type": 8 + }, + "MID360": { + "lidar_net_info": { + "cmd_data_port": 56100, + "push_msg_port": 56200, + "point_data_port": 56300, + "imu_data_port": 56400, + "log_data_port": 56500 + }, + "host_net_info": { + "cmd_data_ip": "192.168.1.50", + "cmd_data_port": 56101, + "push_msg_ip": "192.168.1.50", + "push_msg_port": 56201, + "point_data_ip": "192.168.1.50", + "point_data_port":56301, + "imu_data_ip": "192.168.1.50", + "imu_data_port": 56401, + "log_data_ip": "192.168.1.50", + "log_data_port": 56501 + } + }, + "lidar_configs": [ + { + "ip": "192.168.1.1XX", + "_comment": "REPLACE 1XX with the last octet printed on the label of your Mid-360 unit", + "pcl_data_type": 1, + "pattern_mode": 0, + "extrinsic_parameter": { + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "x": 0.0, + "y": 0.0, + "z": 0.0 + } + } + ] +} diff --git a/control_ws/src/lotti_control/bringup/config/lotti_servo_config.yaml b/control_ws/src/lotti_control/bringup/config/lotti_servo_config.yaml new file mode 100644 index 0000000..e59b6f5 --- /dev/null +++ b/control_ws/src/lotti_control/bringup/config/lotti_servo_config.yaml @@ -0,0 +1,71 @@ +############################################### +# Modify all parameters related to servoing here +############################################### +use_gazebo: false # Whether the robot is started in a Gazebo simulation environment + +## Properties of incoming commands +command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s +scale: + # Scale parameters are only used if command_in_type=="unitless" + linear: 0.2 # Max linear velocity. Unit is [m/s]. Only used for Cartesian commands. + rotational: 0.2 # Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands. + # Max joint angular/linear velocity. Only used for joint commands on joint_command_in_topic. + joint: 1.0 + +# Optionally override Servo's internal velocity scaling when near singularity or collision (0.0 = use internal velocity scaling) +# override_velocity_scaling_factor = 0.0 # valid range [0.0:1.0] + +## Properties of outgoing commands +publish_period: 0.05 # 1/Nominal publish rate [seconds] +low_latency_mode: false # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored) + +# What type of topic does your robot driver expect? +# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory +command_out_type: trajectory_msgs/JointTrajectory + +# What to publish? Can save some bandwidth as most robots only require positions or velocities +publish_joint_positions: true +publish_joint_velocities: true +publish_joint_accelerations: false + +## Plugins for smoothing outgoing commands +smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin" + +# If is_primary_planning_scene_monitor is set to true, the Servo server's PlanningScene advertises the /get_planning_scene service, +# which other nodes can use as a source for information about the planning environment. +# NOTE: If a different node in your system is responsible for the "primary" planning scene instance (e.g. the MoveGroup node), +# then is_primary_planning_scene_monitor needs to be set to false. +is_primary_planning_scene_monitor: true + +## MoveIt properties +move_group_name: lotti_arm_group # Often 'manipulator' or 'arm' +planning_frame: body_link # The MoveIt planning frame. Often 'base_link' or 'world' + +## Other frames +ee_frame_name: arm_link6_link # The name of the end effector link, used to return the EE pose +robot_link_command_frame: body_link # commands must be given in the frame of a robot link. Usually either the base or end effector + +## Stopping behaviour +incoming_command_timeout: 1.0 # Stop servoing if X seconds elapse without a new command +# If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish. +# Important because ROS may drop some messages and we need the robot to halt reliably. +num_outgoing_halt_msgs_to_publish: 4 + +## Configure handling of singularities and joint limits +lower_singularity_threshold: 90.0 # Start decelerating when the condition number hits this (close to singularity) +hard_stop_singularity_threshold: 100.0 # Stop when the condition number hits this +joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. +leaving_singularity_threshold_multiplier: 2.0 # Multiply the hard stop limit by this when leaving singularity (see https://github.com/ros-planning/moveit2/pull/620) + +## Topic names +cartesian_command_in_topic: cmd/arm/joy_twiststamped # Topic for incoming Cartesian twist commands +joint_command_in_topic: cmd/arm/joy_joint # Topic for incoming joint angle commands +joint_topic: /joint_states +status_topic: ~/status # Publish status to this topic +command_out_topic: /arm_controller/joint_trajectory # Publish outgoing commands here + +## Collision checking for the entire robot body +check_collisions: false # Check collisions? +collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. +self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m] +scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/control_ws/src/lotti_control/bringup/config/nav2_params.yaml b/control_ws/src/lotti_control/bringup/config/nav2_params.yaml new file mode 100644 index 0000000..1215cf4 --- /dev/null +++ b/control_ws/src/lotti_control/bringup/config/nav2_params.yaml @@ -0,0 +1,237 @@ +# Nav2 parameters for ResQBot (Lotti) +# Chain drive only - no flipper control during autonomous navigation +# +# Topic remappings assumed (set in operator.launch.py): +# Nav2 publishes /cmd_vel → remapped to /chain_controller/cmd_vel +# diff_drive_ctrl publishes /chain_controller/odom → nav2 reads odom_topic below + +bt_navigator: + ros__parameters: + use_sim_time: false + global_frame: map + robot_base_frame: body_link + odom_topic: /chain_controller/odom + bt_loop_duration: 10 + default_server_timeout: 20 + navigators: ["navigate_to_pose", "navigate_through_poses"] + navigate_to_pose: + plugin: "nav2_bt_navigator::NavigateToPoseNavigator" + navigate_through_poses: + plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" + +controller_server: + ros__parameters: + use_sim_time: false + controller_frequency: 10.0 + min_x_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 + min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 + progress_checker_plugin: "progress_checker" + goal_checker_plugins: ["general_goal_checker"] + controller_plugins: ["FollowPath"] + + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.5 + movement_time_allowance: 10.0 + + general_goal_checker: + plugin: "nav2_controller::SimpleGoalChecker" + xy_goal_tolerance: 0.25 + yaw_goal_tolerance: 0.25 + stateful: true + + FollowPath: + plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" + desired_linear_vel: 0.3 + lookahead_dist: 0.6 + min_lookahead_dist: 0.3 + max_lookahead_dist: 0.9 + lookahead_time: 1.5 + rotate_to_heading_angular_vel: 0.5 + transform_tolerance: 0.1 + use_velocity_scaled_lookahead_dist: false + min_approach_linear_velocity: 0.05 + approach_velocity_scaling_dist: 0.6 + use_collision_detection: true + max_allowed_time_to_collision_up_to_carrot: 1.0 + use_regulated_linear_velocity_scaling: true + use_fixed_curvature_lookahead: false + curvature_feedback_gain: 3.5 + inflation_cost_scaling_factor: 3.0 + use_cost_regulated_linear_velocity_scaling: false + regulated_linear_scaling_min_radius: 0.9 + regulated_linear_scaling_min_speed: 0.25 + use_rotate_to_heading: true + allow_reversing: false + rotate_to_heading_min_angle: 0.785 + max_angular_accel: 1.0 + max_robot_pose_search_dist: 10.0 + +local_costmap: + local_costmap: + ros__parameters: + update_frequency: 5.0 + publish_frequency: 2.0 + global_frame: odom + robot_base_frame: body_link + use_sim_time: false + rolling_window: true + width: 5 + height: 5 + resolution: 0.05 + robot_radius: 0.45 # half the robot body width (0.33m/2 + track width) + plugins: ["obstacle_layer", "inflation_layer"] + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: true + observation_sources: scan pointcloud + scan: + topic: /scan + sensor_frame: lidar_link + data_type: LaserScan + marking: true + clearing: true + obstacle_max_range: 20.0 + obstacle_min_range: 0.1 + raytrace_max_range: 25.0 + raytrace_min_range: 0.0 + pointcloud: + topic: /livox/lidar + sensor_frame: lidar_link + data_type: PointCloud2 + marking: true + clearing: false # let LaserScan handle clearing + min_obstacle_height: 0.05 + max_obstacle_height: 1.5 + obstacle_max_range: 20.0 + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.55 + always_send_full_costmap: true + +global_costmap: + global_costmap: + ros__parameters: + update_frequency: 1.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: body_link + use_sim_time: false + robot_radius: 0.45 + resolution: 0.05 + track_unknown_space: true + plugins: ["static_layer", "obstacle_layer", "inflation_layer"] + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: true + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: true + observation_sources: scan pointcloud + scan: + topic: /scan + sensor_frame: lidar_link + data_type: LaserScan + marking: true + clearing: true + obstacle_max_range: 20.0 + pointcloud: + topic: /livox/lidar + sensor_frame: lidar_link + data_type: PointCloud2 + marking: true + clearing: false + min_obstacle_height: 0.05 + max_obstacle_height: 1.5 + obstacle_max_range: 20.0 + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.55 + always_send_full_costmap: true + +map_server: + ros__parameters: + use_sim_time: false + yaml_filename: "" + +map_saver: + ros__parameters: + use_sim_time: false + save_map_timeout: 5.0 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: true + +planner_server: + ros__parameters: + expected_planner_frequency: 20.0 + use_sim_time: false + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner::NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + +smoother_server: + ros__parameters: + use_sim_time: false + smoother_plugins: ["simple_smoother"] + simple_smoother: + plugin: "nav2_smoother::SimpleSmoother" + tolerance: 1.0e-10 + max_its: 1000 + do_refinement: true + +behavior_server: + ros__parameters: + costmap_topic: local_costmap/costmap_raw + footprint_topic: local_costmap/published_footprint + cycle_frequency: 10.0 + behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] + spin: + plugin: "nav2_behaviors::Spin" + backup: + plugin: "nav2_behaviors::BackUp" + drive_on_heading: + plugin: "nav2_behaviors::DriveOnHeading" + wait: + plugin: "nav2_behaviors::Wait" + global_frame: odom + robot_base_frame: body_link + transform_timeout: 0.1 + use_sim_time: false + simulate_ahead_time: 2.0 + max_rotational_vel: 0.5 + min_rotational_vel: 0.4 + rotational_acc_lim: 1.0 + +waypoint_follower: + ros__parameters: + use_sim_time: false + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: true + waypoint_pause_duration: 200 + +velocity_smoother: + ros__parameters: + use_sim_time: false + smoothing_frequency: 20.0 + scale_velocities: false + feedback: "OPEN_LOOP" + max_velocity: [0.5, 0.0, 1.0] + min_velocity: [-0.5, 0.0, -1.0] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: /chain_controller/odom + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 diff --git a/control_ws/src/lotti_control/bringup/config/slam_toolbox_params.yaml b/control_ws/src/lotti_control/bringup/config/slam_toolbox_params.yaml new file mode 100644 index 0000000..2aa1e38 --- /dev/null +++ b/control_ws/src/lotti_control/bringup/config/slam_toolbox_params.yaml @@ -0,0 +1,60 @@ +slam_toolbox: + ros__parameters: + # Solver + solver_plugin: solver_plugins::CeresSolver + ceres_linear_solver: SPARSE_NORMAL_CHOLESKY + ceres_preconditioner: SCHUR_JACOBI + ceres_trust_strategy: LEVENBERG_MARQUARDT + ceres_dogleg_type: TRADITIONAL_DOGLEG + ceres_loss_function: None + + # ROS frames + odom_frame: odom + map_frame: map + base_frame: body_link + scan_topic: /scan + use_map_saver: true + mode: mapping # switch to "localization" once a map is saved + + # Behaviour + debug_logging: false + throttle_scans: 1 + transform_publish_period: 0.02 # seconds + map_update_interval: 5.0 # seconds + resolution: 0.05 # metres per cell + max_laser_range: 40.0 # Mid-360 max range + minimum_time_interval: 0.5 + transform_timeout: 0.2 + tf_buffer_duration: 30.0 + stack_size_to_use: 40000000 + + # Loop closure + enable_interactive_mode: true + use_scan_matching: true + use_scan_barycenter: true + minimum_travel_distance: 0.5 + minimum_travel_heading: 0.5 + scan_buffer_size: 10 + scan_buffer_maximum_scan_distance: 10.0 + link_match_minimum_response_fine: 0.1 + link_scan_maximum_distance: 1.5 + loop_search_maximum_distance: 3.0 + do_loop_closing: true + loop_match_minimum_chain_size: 10 + loop_match_maximum_variance_coarse: 3.0 + loop_match_minimum_response_coarse: 0.35 + loop_match_minimum_response_fine: 0.45 + correlation_search_space_dimension: 0.5 + correlation_search_space_resolution: 0.01 + correlation_search_space_smear_deviation: 0.1 + loop_search_space_dimension: 8.0 + loop_search_space_resolution: 0.05 + loop_search_space_smear_deviation: 0.03 + distance_variance_penalty: 0.5 + angle_variance_penalty: 1.0 + fine_search_angle_offset: 0.00349 + coarse_search_angle_offset: 0.349 + coarse_angle_resolution: 0.0349 + minimum_angle_penalty: 0.9 + minimum_distance_penalty: 0.5 + use_response_expansion: true diff --git a/control_ws/src/lotti_control/bringup/config/view_lotti.rviz b/control_ws/src/lotti_control/bringup/config/view_lotti.rviz new file mode 100644 index 0000000..3fdce8e --- /dev/null +++ b/control_ws/src/lotti_control/bringup/config/view_lotti.rviz @@ -0,0 +1,345 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Grid1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 363 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" + - Class: rviz_visual_tools/RvizVisualToolsGui + Name: RvizVisualToolsGui +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + arm_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_link1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_link2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_link3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_link4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_link5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm_link6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + body_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flipper_fl_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flipper_fr_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flipper_rl_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flipper_rr_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_main_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_main_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz_default_plugins/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 0.7 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map_updates + Value: true + - Alpha: 0.4 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Global Costmap + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /global_costmap/costmap + Value: true + - Alpha: 0.5 + Class: rviz_default_plugins/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Local Costmap + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_costmap/costmap + Value: true + - Class: rviz_default_plugins/LaserScan + Color: 255; 50; 0 + Color Transformer: FlatColor + Enabled: true + Name: LaserScan + Size (m): 0.05 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /scan + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Class: rviz_default_plugins/PointCloud2 + Color Transformer: AxisColor + Enabled: true + Name: LiDAR PointCloud + Size (m): 0.02 + Style: Points + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /livox/lidar + Value: true + - Class: rviz_default_plugins/Path + Color: 0; 255; 0 + Enabled: true + Name: Global Plan + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /plan + Value: true + - Class: rviz_default_plugins/Path + Color: 0; 100; 255 + Enabled: true + Name: Local Plan + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /local_plan + Value: true + Enabled: true + Global Options: + Background Color: 119; 118; 123 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 1.0388315916061401 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.015883082523941994 + Y: 0.04515325650572777 + Z: 0.25667673349380493 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.10979729890823364 + Target Frame: body_link + Value: Orbit (rviz_default_plugins) + Yaw: 1.4686065912246704 + Saved: ~ +Window Geometry: + Displays: + collapsed: true + Height: 1043 + Hide Left Dock: true + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001640000039efc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d0000039e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000024005200760069007a00560069007300750061006c0054006f006f006c0073004700750069000000039a000000410000004100ffffff000000010000010f000002effc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002ef000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073a0000003efc0100000002fb0000000800540069006d006500000000000000073a000002fb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000780000003e000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730000000000ffffffff0000000000000000 + RvizVisualToolsGui: + collapsed: false + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1920 + X: 0 + Y: 0 diff --git a/control_ws/src/lotti_control/bringup/launch/full.launch.py b/control_ws/src/lotti_control/bringup/launch/full.launch.py new file mode 100644 index 0000000..575ca03 --- /dev/null +++ b/control_ws/src/lotti_control/bringup/launch/full.launch.py @@ -0,0 +1,218 @@ +# Copyright 2023 ros2_control Development Team +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import yaml +from launch import LaunchDescription +from launch.actions import RegisterEventHandler, DeclareLaunchArgument, IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.event_handlers import OnProcessExit +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration + +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from ament_index_python import get_package_share_directory +from moveit_configs_utils import MoveItConfigsBuilder + +def load_yaml(package_name, file_path): + package_path = get_package_share_directory(package_name) + absolute_file_path = os.path.join(package_path, file_path) + + try: + with open(absolute_file_path, "r") as file: + return yaml.safe_load(file) + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + return None + + +def generate_launch_description(): + # Declare arguments + declared_arguments = [] + declared_arguments.append( + DeclareLaunchArgument( + "gui", + default_value="true", + description="Start RViz2 automatically with this launch file.", + ) + ) + + # Get URDF via xacro + robot_description_content = Command([ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution([ + FindPackageShare("lotti_control"), + "description/urdf", + "Lotti.urdf.xacro", + ] + ), + ] + ) + + robot_description = {"robot_description": robot_description_content} + + robot_controllers = PathJoinSubstitution([ + FindPackageShare("lotti_control"), + "config", + "Lotti_controllers.yaml", + ] + ) + + rviz_config_file = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "view_lotti.rviz"] + ) + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + remappings=[ + ("~/robot_description", "/robot_description"), + ], + output="both", + ) + + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + + gui = LaunchConfiguration("gui") + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_config_file], + condition=IfCondition(gui), + ) + + joint_state_broadcaster_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + ) + + arm_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["arm_controller", "-c", "/controller_manager"], + ) + + chain_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["chain_controller", "-c", "/controller_manager"], + ) + + flipper_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["flipper_controller", "-c", "/controller_manager"], + ) + + # Delay rviz start after `joint_state_broadcaster` + delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[rviz_node], + ) + ) + + # Delay start of joint_state_broadcaster after `robot_controller` + # TODO(anyone): This is a workaround for flaky tests. Remove when fixed. + delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=arm_controller_spawner, + on_exit=[joint_state_broadcaster_spawner], + ) + ) + + delay_chain_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=arm_controller_spawner, + on_exit=[chain_controller_spawner], + ) + ) + + delay_flipper_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=chain_controller_spawner, + on_exit=[flipper_controller_spawner], + ) + ) + + # Get parameters for the Servo node + servo_yaml = load_yaml("lotti_control", "config/lotti_servo_config.yaml") + servo_params = {"moveit_servo": servo_yaml} + + moveit_config = ( + MoveItConfigsBuilder("lotti") + .robot_description(file_path="config/Lotti.urdf.xacro") + .to_moveit_configs() + ) + + servo_node = Node( + package="moveit_servo", + executable="servo_node_main", + parameters=[ + servo_params, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], + output="screen", + ) + + delay_servo_node = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[servo_node], + ) + ) + + teleop_package = get_package_share_directory('lotti_teleop') + + teleop_node = IncludeLaunchDescription( + os.path.join(teleop_package, 'launch', 'teleop_launch.py'), + ) + + delay_teleop = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[teleop_node], + ) + ) + + joy_node = Node( + package='joy', + executable='joy_node', + ) + + nodes = [ + control_node, + robot_state_pub_node, + arm_controller_spawner, + #delay_chain_controller_spawner, + #delay_flipper_controller_spawner, + delay_rviz_after_joint_state_broadcaster_spawner, + delay_joint_state_broadcaster_after_robot_controller_spawner, + delay_servo_node, + joy_node, + delay_teleop, + ] + + return LaunchDescription(declared_arguments + nodes) diff --git a/control_ws/src/lotti_control/bringup/launch/operator.launch.py b/control_ws/src/lotti_control/bringup/launch/operator.launch.py new file mode 100644 index 0000000..614308c --- /dev/null +++ b/control_ws/src/lotti_control/bringup/launch/operator.launch.py @@ -0,0 +1,264 @@ +# Copyright 2023 ros2_control Development Team +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import yaml +from launch import LaunchDescription +from launch.actions import RegisterEventHandler, DeclareLaunchArgument, IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.event_handlers import OnProcessExit +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration + +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from ament_index_python import get_package_share_directory +from moveit_configs_utils import MoveItConfigsBuilder + +# ── NOTE ───────────────────────────────────────────────────────────────────── +# operator.launch.py → runs on the OPERATOR PC (Ubuntu, same ROS_DOMAIN_ID) +# robot.launch.py → runs on the ROBOT PC (NUC100 mini PC) +# ───────────────────────────────────────────────────────────────────────────── + +def load_yaml(package_name, file_path): + package_path = get_package_share_directory(package_name) + absolute_file_path = os.path.join(package_path, file_path) + + try: + with open(absolute_file_path, "r") as file: + return yaml.safe_load(file) + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + return None + + +def generate_launch_description(): + # Declare arguments + declared_arguments = [] + declared_arguments.append( + DeclareLaunchArgument( + "gui", + default_value="true", + description="Start RViz2 automatically with this launch file.", + ) + ) + + # Get URDF via xacro + robot_description_content = Command([ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution([ + FindPackageShare("lotti_control"), + "description/urdf", + "Lotti.urdf.xacro", + ] + ), + ] + ) + + robot_description = {"robot_description": robot_description_content} + + robot_controllers = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "Lotti_controllers.yaml"] + ) + + rviz_config_file = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "view_lotti.rviz"] + ) + + controller_manager = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + remappings=[ + ("~/robot_description", "/robot_description"), + ], + output="both", + ) + + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + + gui = LaunchConfiguration("gui") + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_config_file], + condition=IfCondition(gui), + ) + + joint_state_broadcaster_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + ) + + arm_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["arm_controller", "-c", "/controller_manager"], + ) + + chain_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["chain_controller", "-c", "/controller_manager"], + ) + + flipper_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["flipper_controller", "-c", "/controller_manager"], + ) + + # Delay rviz start after `joint_state_broadcaster` + delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[rviz_node], + ) + ) + + # Delay start of joint_state_broadcaster after `robot_controller` + # TODO(anyone): This is a workaround for flaky tests. Remove when fixed. + delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=arm_controller_spawner, + on_exit=[joint_state_broadcaster_spawner], + ) + ) + + delay_chain_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=arm_controller_spawner, + on_exit=[chain_controller_spawner], + ) + ) + + delay_flipper_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=chain_controller_spawner, + on_exit=[flipper_controller_spawner], + ) + ) + + # Get parameters for the Servo node + servo_yaml = load_yaml("lotti_control", "config/lotti_servo_config.yaml") + servo_params = {"moveit_servo": servo_yaml} + + moveit_config = ( + MoveItConfigsBuilder("lotti") + .robot_description(file_path="config/Lotti.urdf.xacro") + .to_moveit_configs() + ) + + servo_node = Node( + package="moveit_servo", + executable="servo_node_main", + parameters=[ + servo_params, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], + output="screen", + ) + + delay_servo_node = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[servo_node], + ) + ) + + teleop_package = get_package_share_directory('lotti_teleop') + + teleop_node = IncludeLaunchDescription( + os.path.join(teleop_package, 'launch', 'teleop_launch.py'), + ) + + delay_teleop = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[teleop_node], + ) + ) + + joy_node = Node( + package='joy', + executable='joy_node', + ) + + # ── slam_toolbox (online async SLAM — builds map + localizes simultaneously) + slam_toolbox = IncludeLaunchDescription( + os.path.join( + get_package_share_directory('slam_toolbox'), + 'launch', 'online_async_launch.py' + ), + launch_arguments={ + 'use_sim_time': 'false', + 'slam_params_file': os.path.join( + get_package_share_directory('lotti_control'), + 'config', 'slam_toolbox_params.yaml' + ), + }.items(), + ) + + # ── Nav2 navigation stack ──────────────────────────────────────────────── + nav2_params = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "nav2_params.yaml" + ]) + + nav2 = IncludeLaunchDescription( + os.path.join( + get_package_share_directory('nav2_bringup'), + 'launch', 'navigation_launch.py' + ), + launch_arguments={ + 'use_sim_time': 'false', + 'params_file': nav2_params, + }.items(), + ) + + # Nav2 publishes /cmd_vel, diff_drive_controller subscribes to + # /chain_controller/cmd_vel. The remapping node bridges the two. + cmd_vel_relay = Node( + package='topic_tools', + executable='relay', + name='cmd_vel_relay', + parameters=[{'input_topic': '/cmd_vel', + 'output_topic': '/chain_controller/cmd_vel'}], + ) + + nodes = [ + #controller_manager, + robot_state_pub_node, + arm_controller_spawner, + delay_chain_controller_spawner, + delay_flipper_controller_spawner, + delay_rviz_after_joint_state_broadcaster_spawner, + delay_joint_state_broadcaster_after_robot_controller_spawner, + delay_servo_node, + joy_node, + delay_teleop, + slam_toolbox, + nav2, + cmd_vel_relay, + ] + + return LaunchDescription(declared_arguments + nodes) diff --git a/control_ws/src/lotti_control/bringup/launch/robot.launch.py b/control_ws/src/lotti_control/bringup/launch/robot.launch.py new file mode 100644 index 0000000..8029d97 --- /dev/null +++ b/control_ws/src/lotti_control/bringup/launch/robot.launch.py @@ -0,0 +1,264 @@ +# Copyright 2023 ros2_control Development Team +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import yaml +from launch import LaunchDescription +from launch.actions import RegisterEventHandler, DeclareLaunchArgument, IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.event_handlers import OnProcessExit +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration + +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from ament_index_python import get_package_share_directory +from moveit_configs_utils import MoveItConfigsBuilder + +# ── NOTE ───────────────────────────────────────────────────────────────────── +# robot.launch.py → runs on the ROBOT PC (NUC100 mini PC) +# operator.launch.py → runs on the OPERATOR PC +# ───────────────────────────────────────────────────────────────────────────── + +def load_yaml(package_name, file_path): + package_path = get_package_share_directory(package_name) + absolute_file_path = os.path.join(package_path, file_path) + + try: + with open(absolute_file_path, "r") as file: + return yaml.safe_load(file) + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available + return None + + +def generate_launch_description(): + # Declare arguments + declared_arguments = [] + declared_arguments.append( + DeclareLaunchArgument( + "gui", + default_value="true", + description="Start RViz2 automatically with this launch file.", + ) + ) + + # Get URDF via xacro + robot_description_content = Command([ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution([ + FindPackageShare("lotti_control"), + "description/urdf", + "Lotti.urdf.xacro", + ] + ), + ] + ) + + robot_description = {"robot_description": robot_description_content} + + robot_controllers = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "Lotti_controllers.yaml"] + ) + + rviz_config_file = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "view_lotti.rviz"] + ) + + controller_manager = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + remappings=[("~/robot_description", "/robot_description"),], + output="both", + ) + + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + + gui = LaunchConfiguration("gui") + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_config_file], + condition=IfCondition(gui), + ) + + joint_state_broadcaster_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + ) + + arm_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["arm_controller", "-c", "/controller_manager"], + ) + + chain_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["chain_controller", "-c", "/controller_manager"], + ) + + flipper_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["flipper_controller", "-c", "/controller_manager"], + ) + + # Delay rviz start after `joint_state_broadcaster` + delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[rviz_node], + ) + ) + + # Delay start of joint_state_broadcaster after `robot_controller` + # TODO(anyone): This is a workaround for flaky tests. Remove when fixed. + delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=arm_controller_spawner, + on_exit=[joint_state_broadcaster_spawner], + ) + ) + + delay_chain_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=arm_controller_spawner, + on_exit=[chain_controller_spawner], + ) + ) + + delay_flipper_controller_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=chain_controller_spawner, + on_exit=[flipper_controller_spawner], + ) + ) + + # Get parameters for the Servo node + servo_yaml = load_yaml("lotti_control", "config/lotti_servo_config.yaml") + servo_params = {"moveit_servo": servo_yaml} + + moveit_config = ( + MoveItConfigsBuilder("lotti") + .robot_description(file_path="config/Lotti.urdf.xacro") + .to_moveit_configs() + ) + + servo_node = Node( + package="moveit_servo", + executable="servo_node_main", + parameters=[ + servo_params, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, + ], + output="screen", + ) + + delay_servo_node = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[servo_node], + ) + ) + + teleop_package = get_package_share_directory('lotti_teleop') + + teleop_node = IncludeLaunchDescription( + os.path.join(teleop_package, 'launch', 'teleop_launch.py'), + ) + + delay_teleop = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[teleop_node], + ) + ) + + joy_node = Node( + package='joy', + executable='joy_node', + ) + + # ── Livox Mid-360 driver ───────────────────────────────────────────────── + livox_config = PathJoinSubstitution([ + FindPackageShare("lotti_control"), "config", "MID360_config.json" + ]) + + livox_driver = Node( + package='livox_ros_driver2', + executable='livox_ros_driver2_node', + name='livox_lidar_publisher', + parameters=[{ + 'user_config_path': livox_config, + 'xfer_format': 0, # 0 = PointCloud2, 1 = CustomMsg + 'multi_topic': 0, + 'data_src': 0, + 'publish_freq': 10.0, + 'output_data_type': 0, + 'frame_id': 'lidar_link', + }], + output='screen', + ) + + # ── PointCloud2 → LaserScan (for slam_toolbox on operator PC) ──────────── + # Uses body_link as target so the horizontal slice is robot-relative + # regardless of the sensor's 30° pitch tilt. + pointcloud_to_laserscan = Node( + package='pointcloud_to_laserscan', + executable='pointcloud_to_laserscan_node', + name='pointcloud_to_laserscan', + parameters=[{ + 'target_frame': 'body_link', + 'transform_tolerance': 0.01, + 'min_height': 0.0, + 'max_height': 0.5, # horizontal band in body_link frame + 'angle_min': -3.14159, + 'angle_max': 3.14159, + 'angle_increment': 0.00872, # ~0.5 deg resolution + 'scan_time': 0.1, + 'range_min': 0.1, + 'range_max': 40.0, + 'use_inf': True, + }], + remappings=[('/cloud_in', '/livox/lidar')], + ) + + nodes = [ + controller_manager, + #robot_state_pub_node, + #arm_controller_spawner, + #delay_chain_controller_spawner, + #delay_flipper_controller_spawner, + #delay_rviz_after_joint_state_broadcaster_spawner, + #delay_joint_state_broadcaster_after_robot_controller_spawner, + #delay_servo_node, + #joy_node, + #delay_teleop, + livox_driver, + pointcloud_to_laserscan, + ] + + return LaunchDescription(declared_arguments + nodes) diff --git a/control_ws/src/lotti_control/description/launch/view_lotti.launch.py b/control_ws/src/lotti_control/description/launch/view_lotti.launch.py new file mode 100644 index 0000000..1cf66e4 --- /dev/null +++ b/control_ws/src/lotti_control/description/launch/view_lotti.launch.py @@ -0,0 +1,84 @@ +# Copyright 2023 ros2_control Development Team +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + # Declare arguments + declared_arguments = [] + declared_arguments.append( + DeclareLaunchArgument( + "gui", + default_value="true", + description="Start Rviz2 and Joint State Publisher gui automatically \ + with this launch file.", + ) + ) + # Initialize Arguments + gui = LaunchConfiguration("gui") + + # Get URDF via xacro + robot_description_content = Command( + [ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution( + [ + FindPackageShare("lotti_control"), + "urdf", + "lotti_main.urdf.xacro", + ] + ), + ] + ) + robot_description = {"robot_description": robot_description_content} + + rviz_config_file = PathJoinSubstitution( + [FindPackageShare("lotti_control"), "config", "view_lotti.rviz"] + ) + + joint_state_publisher_node = Node( + package="joint_state_publisher_gui", + executable="joint_state_publisher_gui", + condition=IfCondition(gui), + ) + + robot_state_publisher_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_config_file], + condition=IfCondition(gui), + ) + # + nodes_to_start = [ + joint_state_publisher_node, + robot_state_publisher_node, + rviz_node, + ] + + return LaunchDescription(declared_arguments + nodes_to_start) diff --git a/control_ws/src/lotti_control/description/meshes/arm_base_link.STL b/control_ws/src/lotti_control/description/meshes/arm_base_link.STL new file mode 100644 index 0000000..de736dc Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_base_link.STL differ diff --git a/control_ws/src/lotti_control/description/meshes/arm_link1_link.STL b/control_ws/src/lotti_control/description/meshes/arm_link1_link.STL new file mode 100644 index 0000000..343c61a Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_link1_link.STL differ diff --git a/control_ws/src/lotti_control/description/meshes/arm_link2_link.STL b/control_ws/src/lotti_control/description/meshes/arm_link2_link.STL new file mode 100644 index 0000000..20d3e2c Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_link2_link.STL differ diff --git a/control_ws/src/lotti_control/description/meshes/arm_link3_link.STL b/control_ws/src/lotti_control/description/meshes/arm_link3_link.STL new file mode 100644 index 0000000..1c1393d Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_link3_link.STL differ diff --git a/control_ws/src/lotti_control/description/meshes/arm_link4_link.STL b/control_ws/src/lotti_control/description/meshes/arm_link4_link.STL new file mode 100644 index 0000000..ec8bb3d Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_link4_link.STL differ diff --git a/control_ws/src/lotti_control/description/meshes/arm_link5_link.STL b/control_ws/src/lotti_control/description/meshes/arm_link5_link.STL new file mode 100644 index 0000000..2334a3c Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_link5_link.STL differ diff --git a/control_ws/src/lotti_control/description/meshes/arm_link6_link.STL b/control_ws/src/lotti_control/description/meshes/arm_link6_link.STL new file mode 100644 index 0000000..1c1edc8 Binary files /dev/null and b/control_ws/src/lotti_control/description/meshes/arm_link6_link.STL differ diff --git a/control_ws/src/lotti_control/description/ros2_control/Lotti.ros_control.xacro b/control_ws/src/lotti_control/description/ros2_control/Lotti.ros_control.xacro new file mode 100644 index 0000000..55a6f4e --- /dev/null +++ b/control_ws/src/lotti_control/description/ros2_control/Lotti.ros_control.xacro @@ -0,0 +1,122 @@ + + + + + + + + arm_interface/ArmInterface + /dev/serial/by-id/usb-Arduino__www.arduino.cc__0042_950353139353515082C1-if00 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + flipper_interface/FlipperInterface + /dev/serial/by-id/usb-Arduino__www.arduino.cc__0043_8503331313735151A0F0-if00 + + + + + + + + + + + + + + + + + + + + + + + + + + + + diffdrive_lotti/DiffDriveLotti + left_chain_joint + right_chain_joint + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/description/srdf/Lotti.srdf.xacro b/control_ws/src/lotti_control/description/srdf/Lotti.srdf.xacro new file mode 100644 index 0000000..6524199 --- /dev/null +++ b/control_ws/src/lotti_control/description/srdf/Lotti.srdf.xacro @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/description/srdf/lotti_arm_group.xacro b/control_ws/src/lotti_control/description/srdf/lotti_arm_group.xacro new file mode 100644 index 0000000..b290707 --- /dev/null +++ b/control_ws/src/lotti_control/description/srdf/lotti_arm_group.xacro @@ -0,0 +1,40 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control_ws/src/lotti_control/description/srdf/lotti_body_group.xacro b/control_ws/src/lotti_control/description/srdf/lotti_body_group.xacro new file mode 100644 index 0000000..5247b7e --- /dev/null +++ b/control_ws/src/lotti_control/description/srdf/lotti_body_group.xacro @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control_ws/src/lotti_control/description/urdf/Lotti.urdf.xacro b/control_ws/src/lotti_control/description/urdf/Lotti.urdf.xacro new file mode 100644 index 0000000..4d7248f --- /dev/null +++ b/control_ws/src/lotti_control/description/urdf/Lotti.urdf.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/description/urdf/Lotti_arm.xacro b/control_ws/src/lotti_control/description/urdf/Lotti_arm.xacro new file mode 100644 index 0000000..71e21ff --- /dev/null +++ b/control_ws/src/lotti_control/description/urdf/Lotti_arm.xacro @@ -0,0 +1,252 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/description/urdf/Lotti_body.xacro b/control_ws/src/lotti_control/description/urdf/Lotti_body.xacro new file mode 100644 index 0000000..05fc74d --- /dev/null +++ b/control_ws/src/lotti_control/description/urdf/Lotti_body.xacro @@ -0,0 +1,211 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control_ws/src/lotti_control/description/urdf/Lotti_lidar.xacro b/control_ws/src/lotti_control/description/urdf/Lotti_lidar.xacro new file mode 100644 index 0000000..3d4b6af --- /dev/null +++ b/control_ws/src/lotti_control/description/urdf/Lotti_lidar.xacro @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/description/urdf/urdf_inertial_shapes.xacro b/control_ws/src/lotti_control/description/urdf/urdf_inertial_shapes.xacro new file mode 100644 index 0000000..3099c2a --- /dev/null +++ b/control_ws/src/lotti_control/description/urdf/urdf_inertial_shapes.xacro @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/description/urdf/urdf_materials.xacro b/control_ws/src/lotti_control/description/urdf/urdf_materials.xacro new file mode 100644 index 0000000..2675a78 --- /dev/null +++ b/control_ws/src/lotti_control/description/urdf/urdf_materials.xacro @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/control_ws/src/lotti_control/hardware/arm_interface.cpp b/control_ws/src/lotti_control/hardware/arm_interface.cpp new file mode 100644 index 0000000..54da6cb --- /dev/null +++ b/control_ws/src/lotti_control/hardware/arm_interface.cpp @@ -0,0 +1,201 @@ +#include "lotti_control/arm_interface.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "sstream" +#include + +#include "hardware_interface/lexical_casts.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/rclcpp.hpp" + +namespace arm_interface +{ + CallbackReturn ArmInterface::on_init(const hardware_interface::HardwareInfo & info) + { + if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) + { + return CallbackReturn::ERROR; + } + + //get the Arduino ID from the ros2_control file +//- + device_ = info_.hardware_parameters["device"]; + + // robot has 6 joints, 4 interfaces + joint_positions_.assign(6, 0); + joint_velocities_.assign(6, 0); + joint_torques_.assign(6, 0); + joint_volts_.assign(6, 0); + joint_positions_command_.assign(6, 0); + joint_velocities_command_.assign(6, 0); + + for (const auto & joint : info_.joints) + { + for (const auto & interface : joint.state_interfaces) + { + joint_interfaces[interface.name].push_back(joint.name); + } + } + + return CallbackReturn::SUCCESS; + } + + std::vector ArmInterface::export_state_interfaces(){ + std::vector state_interfaces; + + int ind = 0; + for (const auto &joint_name : joint_interfaces["position"]){ + state_interfaces.emplace_back(joint_name, "position", &joint_positions_[ind++]); + } + + ind = 0; + for (const auto &joint_name : joint_interfaces["velocity"]){ + state_interfaces.emplace_back(joint_name, "velocity", &joint_velocities_[ind++]); + } + + ind = 0; + for (const auto &joint_name : joint_interfaces["torque"]){ + state_interfaces.emplace_back(joint_name, "torque", &joint_torques_[ind++]); + } + + ind = 0; + for (const auto &joint_name : joint_interfaces["volt"]){ + state_interfaces.emplace_back(joint_name, "volt", &joint_volts_[ind++]); + } + + return state_interfaces; + } + + std::vector ArmInterface::export_command_interfaces(){ + std::vector command_interfaces; + + int ind = 0; + for (const auto &joint_name : joint_interfaces["position"]){ + command_interfaces.emplace_back(joint_name, "position", &joint_positions_command_[ind++]); + } + + ind = 0; + for (const auto &joint_name : joint_interfaces["velocity"]){ + command_interfaces.emplace_back(joint_name, "velocity", &joint_velocities_command_[ind++]); + } + + return command_interfaces; + } + + hardware_interface::CallbackReturn ArmInterface::on_configure(const rclcpp_lifecycle::State & previous_state){ + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Configuring ...please wait..."); + +//- + if (arm_comms_.connected()){ +//- + arm_comms_.disconnect(); +//- + } +//- + arm_comms_.connect(device_); + + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Successfully configured!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn ArmInterface::on_cleanup(const rclcpp_lifecycle::State & previous_state){ + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Cleaning up ...please wait..."); + +//- + if (arm_comms_.connected()){ +//- + arm_comms_.disconnect(); +//- + } + + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Successfully cleaned up!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn ArmInterface::on_activate(const rclcpp_lifecycle::State & previous_state){ + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Activating ...please wait..."); + +//- + if (!arm_comms_.connected()){ +//- + RCLCPP_ERROR(rclcpp::get_logger("ArmInterface"), "Arduino not connected"); +//- + return hardware_interface::CallbackReturn::ERROR; +//- + } + + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Successfully activated!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn ArmInterface::on_deactivate(const rclcpp_lifecycle::State & previous_state){ + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Deactivating ...please wait..."); + + + RCLCPP_INFO(rclcpp::get_logger("ArmInterface"), "Successfully deactivated!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + return_type ArmInterface::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & period){ +//- + if (!arm_comms_.connected()){ +//- + return hardware_interface::return_type::ERROR; +//- + } + +//- + std::string arm_answer_ = arm_comms_.read_msg(); + +//- + sscanf(arm_answer_.c_str(), "%lf/%lf/%lf/%lf/%lf/%lf", &state_pos_[0], &state_pos_[1], &state_pos_[2], &state_pos_[3], &state_pos_[4], &state_pos_[5]); + + for (auto i = 0ul; i < joint_velocities_command_.size(); i++){ + joint_velocities_[i] = joint_velocities_command_[i]; + } + +//- for (auto i = 0ul; i < joint_positions_.size(); i++){ +//- joint_positions_[i] = (state_pos_[i]/2048)*3,1416; +//- } + +//+ + for (auto i = 0ul; i < joint_positions_.size(); i++){ +//+ + joint_positions_[i] = joint_positions_command_[i]; +//+ + } + + + return return_type::OK; + } + + return_type ArmInterface::write(const rclcpp::Time &, const rclcpp::Duration &){ + + std::stringstream msg; + + for (auto i = 0ul; i < joint_positions_command_.size(); i++){ + command_positions[i]= int((joint_positions_command_[i]/3.1416) * 2048); + command_velocities[i]= int(abs(joint_velocities_command_[i] * 200)); + } + + +//- + arm_comms_.set_arm_values(command_positions, command_velocities); + + return return_type::OK; + } + +} // namespace arm_interface + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + arm_interface::ArmInterface, hardware_interface::SystemInterface) diff --git a/control_ws/src/lotti_control/hardware/diffbot_system.cpp b/control_ws/src/lotti_control/hardware/diffbot_system.cpp new file mode 100644 index 0000000..5f0c1e4 --- /dev/null +++ b/control_ws/src/lotti_control/hardware/diffbot_system.cpp @@ -0,0 +1,176 @@ +// Copyright 2021 ros2_control Development Team +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "lotti_control/diffbot_system.hpp" + +#include +#include +#include +#include +#include + +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/rclcpp.hpp" + +namespace diffdrive_lotti{ + hardware_interface::CallbackReturn DiffDriveLotti::on_init( + const hardware_interface::HardwareInfo & info){ + if (hardware_interface::SystemInterface::on_init(info) != + hardware_interface::CallbackReturn::SUCCESS){ + return hardware_interface::CallbackReturn::ERROR; + } + + cfg_.left_wheel_name = info_.hardware_parameters["left_wheel_name"]; + cfg_.right_wheel_name = info_.hardware_parameters["right_wheel_name"]; + //cfg_.enc_counts_per_rev = std::stoi(info_.hardware_parameters["enc_counts_per_rev"]); + + wheel_l_.setup(cfg_.left_wheel_name, cfg_.enc_counts_per_rev); + wheel_r_.setup(cfg_.right_wheel_name, cfg_.enc_counts_per_rev); + + for (const hardware_interface::ComponentInfo & joint : info_.joints){ + // DiffBotSystem has exactly two states and one command interface on each joint + if (joint.command_interfaces.size() != 1){ + RCLCPP_FATAL( + rclcpp::get_logger("DiffDriveLotti"), + "Joint '%s' has %zu command interfaces found. 1 expected.", joint.name.c_str(), + joint.command_interfaces.size()); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.command_interfaces[0].name != hardware_interface::HW_IF_VELOCITY){ + RCLCPP_FATAL( + rclcpp::get_logger("DiffDriveLotti"), + "Joint '%s' have %s command interfaces found. '%s' expected.", joint.name.c_str(), + joint.command_interfaces[0].name.c_str(), hardware_interface::HW_IF_VELOCITY); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.state_interfaces.size() != 2){ + RCLCPP_FATAL( + rclcpp::get_logger("DiffDriveLotti"), + "Joint '%s' has %zu state interface. 2 expected.", joint.name.c_str(), + joint.state_interfaces.size()); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION){ + RCLCPP_FATAL( + rclcpp::get_logger("DiffDriveLotti"), + "Joint '%s' have '%s' as first state interface. '%s' expected.", joint.name.c_str(), + joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION); + return hardware_interface::CallbackReturn::ERROR; + } + + if (joint.state_interfaces[1].name != hardware_interface::HW_IF_VELOCITY){ + RCLCPP_FATAL( + rclcpp::get_logger("DiffDriveLotti"), + "Joint '%s' have '%s' as second state interface. '%s' expected.", joint.name.c_str(), + joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY); + return hardware_interface::CallbackReturn::ERROR; + } + } + + return hardware_interface::CallbackReturn::SUCCESS; + } + + std::vector DiffDriveLotti::export_state_interfaces(){ + std::vector state_interfaces; + + state_interfaces.emplace_back(hardware_interface::StateInterface( + wheel_l_.name, hardware_interface::HW_IF_POSITION, &wheel_l_.pos)); + state_interfaces.emplace_back(hardware_interface::StateInterface( + wheel_l_.name, hardware_interface::HW_IF_VELOCITY, &wheel_l_.vel)); + + state_interfaces.emplace_back(hardware_interface::StateInterface( + wheel_r_.name, hardware_interface::HW_IF_POSITION, &wheel_r_.pos)); + state_interfaces.emplace_back(hardware_interface::StateInterface( + wheel_r_.name, hardware_interface::HW_IF_VELOCITY, &wheel_r_.vel)); + + return state_interfaces; + } + + std::vector DiffDriveLotti::export_command_interfaces(){ + std::vector command_interfaces; + + command_interfaces.emplace_back(hardware_interface::CommandInterface( + wheel_l_.name, hardware_interface::HW_IF_VELOCITY, &wheel_l_.cmd)); + + command_interfaces.emplace_back(hardware_interface::CommandInterface( + wheel_r_.name, hardware_interface::HW_IF_VELOCITY, &wheel_r_.cmd)); + + return command_interfaces; + } + + hardware_interface::CallbackReturn DiffDriveLotti::on_configure( + const rclcpp_lifecycle::State & /*previous_state*/){ + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Configuring ...please wait..."); + + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Successfully configured!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn DiffDriveLotti::on_cleanup( + const rclcpp_lifecycle::State & /*previous_state*/){ + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Cleaning up ...please wait..."); + + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Successfully cleaned up!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + + hardware_interface::CallbackReturn DiffDriveLotti::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/){ + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Activating ...please wait..."); + + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Successfully activated!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn DiffDriveLotti::on_deactivate( + const rclcpp_lifecycle::State & /*previous_state*/){ + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Deactivating ...please wait..."); + + RCLCPP_INFO(rclcpp::get_logger("DiffDriveLotti"), "Successfully deactivated!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::return_type DiffDriveLotti::read( + const rclcpp::Time & /*time*/, const rclcpp::Duration & period){ + + double delta_seconds = period.seconds(); + + double pos_prev = wheel_l_.pos; + wheel_l_.pos = pos_prev + (wheel_l_.cmd * delta_seconds); + wheel_l_.vel = wheel_l_.cmd; + + pos_prev = wheel_r_.pos; + wheel_r_.pos = pos_prev + (wheel_r_.cmd * delta_seconds); + wheel_r_.vel = wheel_r_.cmd; + + //std::cout << std::to_string(wheel_l_.vel) << std::to_string(wheel_l_.pos) << "\n"; + + return hardware_interface::return_type::OK; + } + + hardware_interface::return_type DiffDriveLotti::write( + const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/){ + + return hardware_interface::return_type::OK; + } + +} // namespace diffdrive_lotti + +#include "pluginlib/class_list_macros.hpp" +PLUGINLIB_EXPORT_CLASS( + diffdrive_lotti::DiffDriveLotti, hardware_interface::SystemInterface) \ No newline at end of file diff --git a/control_ws/src/lotti_control/hardware/flipper_interface.cpp b/control_ws/src/lotti_control/hardware/flipper_interface.cpp new file mode 100644 index 0000000..5b0f7b4 --- /dev/null +++ b/control_ws/src/lotti_control/hardware/flipper_interface.cpp @@ -0,0 +1,153 @@ +#include "lotti_control/flipper_interface.hpp" +//#include "lotti_control/flipper_comms.hpp" +//#include "lotti_control/RS485_comms.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "hardware_interface/lexical_casts.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/rclcpp.hpp" + + +namespace flipper_interface{ + CallbackReturn FlipperInterface::on_init(const hardware_interface::HardwareInfo &info){ + if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS){ + return CallbackReturn::ERROR; + } + + //get the Arduino ID from the ros2_control file + device_ = info_.hardware_parameters["device"]; + + // robot has 4 joints, 2 interfaces + joint_positions_.assign(4, 0); + joint_velocities_command_.assign(4, 0); + + for (const auto &joint : info_.joints){ + for (const auto &interface : joint.state_interfaces){ + joint_interfaces[interface.name].push_back(joint.name); + } + } + return CallbackReturn::SUCCESS; + } + + std::vector FlipperInterface::export_state_interfaces(){ + std::vector state_interfaces; + + int ind = 0; + for (const auto &joint_name : joint_interfaces["position"]){ + state_interfaces.emplace_back(joint_name, "position", &joint_positions_[ind++]); + } + return state_interfaces; + } + + std::vector FlipperInterface::export_command_interfaces(){ + std::vector command_interfaces; + + for (int ind = 0; ind < 4; ind++){ + command_interfaces.emplace_back(info_.joints[ind].name, "velocity", &joint_velocities_command_[ind]); + } + return command_interfaces; + } + + hardware_interface::CallbackReturn FlipperInterface::on_configure(const rclcpp_lifecycle::State &previous_state){ + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Configuring ...please wait..."); + +/* if (flipper_comms_.connected()){ + flipper_comms_.disconnect(); + } + flipper_comms_.connect(device_); + */ + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Successfully configured"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn FlipperInterface::on_cleanup(const rclcpp_lifecycle::State &previous_state){ + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Cleaning up ...please wait..."); + +/* if (flipper_comms_.connected()){ + flipper_comms_.disconnect(); + } */ + + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Successfully cleaned up!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn FlipperInterface::on_activate(const rclcpp_lifecycle::State &previous_state){ + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Configuring ...please wait..."); + + /* if (!flipper_comms_.connected()){ + RCLCPP_ERROR(rclcpp::get_logger("FlipperInterface"), "Arduino not connected"); + return hardware_interface::CallbackReturn::ERROR; + } */ + + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Successfully activated"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + hardware_interface::CallbackReturn FlipperInterface::on_deactivate(const rclcpp_lifecycle::State &previous_state){ + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Deactivating ...please wait..."); + + RCLCPP_INFO(rclcpp::get_logger("FlipperInterface"), "Successfully deactivated!"); + return hardware_interface::CallbackReturn::SUCCESS; + } + + return_type FlipperInterface::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & period){ +/* if (!flipper_comms_.connected()){ + return hardware_interface::return_type::ERROR; + } + + std::string flipper_answer_ = flipper_comms_.read_msg(); + */ + + fl_cmd_ = fl_cmd_ + joint_velocities_command_[1] * period.seconds() * 360/12; + fr_cmd_ = fr_cmd_ + joint_velocities_command_[0] * period.seconds() * 360/12; + rl_cmd_ = rl_cmd_ + joint_velocities_command_[3] * period.seconds() * 360/12; + rr_cmd_ = rr_cmd_ + joint_velocities_command_[2] * period.seconds() * 360/12; + + + std::string flipper_answer_ = + "FL" + std::to_string(fl_cmd_) + + "FR" + std::to_string(fr_cmd_) + + "RL" + std::to_string(rl_cmd_) + + "RR" + std::to_string(rr_cmd_); + + //std::cout << flipper_answer_ << "\n"; + + sscanf(flipper_answer_.c_str(), "FL%fFR%fRL%fRR%f", &fl_state_, &fr_state_, &rl_state_, &rr_state_); + + joint_positions_[0] = (fr_state_ /360) * (2*3.1415); + joint_positions_[1] = (fl_state_ /360) * (2*3.1415); + joint_positions_[2] = (rr_state_ /360) * (2*3.1415); + joint_positions_[3] = (rl_state_ /360) * (2*3.1415); + + return return_type::OK; + } + + return_type FlipperInterface::write(const rclcpp::Time & /*time*/, const rclcpp::Duration &){ + + //std::cout << std::to_string(joint_velocities_command_[0]) << "\n"; + +/* flipper_comms_.set_flipper_values( + joint_velocities_command_[0], + joint_velocities_command_[1], + joint_velocities_command_[2], + joint_velocities_command_[3] + ); */ + + return return_type::OK; + } + +} // namespace flipper_interface + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + flipper_interface::FlipperInterface, hardware_interface::SystemInterface) \ No newline at end of file diff --git a/control_ws/src/lotti_control/hardware/include/lotti_control/arm_interface.hpp b/control_ws/src/lotti_control/hardware/include/lotti_control/arm_interface.hpp new file mode 100644 index 0000000..cd9ebe5 --- /dev/null +++ b/control_ws/src/lotti_control/hardware/include/lotti_control/arm_interface.hpp @@ -0,0 +1,72 @@ +#ifndef ARM_INTERFACE__ARM_INTERFACE_HPP_ +#define ARM_INTERFACE__ARM_INTERFACE_HPP_ + +#include "string" +#include "unordered_map" +#include "vector" + +#include "hardware_interface/handle.hpp" +#include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/system_interface.hpp" +#include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" + +#include "rclcpp/clock.hpp" +#include "rclcpp/duration.hpp" +#include "rclcpp/logger.hpp" +#include "rclcpp/macros.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" + +#include "lotti_control/serial_comms.hpp" + +using hardware_interface::return_type; + +namespace arm_interface +{ + using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + + class HARDWARE_INTERFACE_PUBLIC ArmInterface : public hardware_interface::SystemInterface + { + public: + CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; + + std::vector export_state_interfaces() override; + std::vector export_command_interfaces() override; + + hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; + hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override; + + hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; + hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; + + return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override; + return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override; + + + protected: + /// The size of this vector is (standard_interfaces_.size() x nr_joints) + std::vector joint_velocities_command_; + std::vector joint_positions_command_; + std::vector joint_positions_; + std::vector joint_velocities_; + std::vector joint_torques_; + std::vector joint_volts_; + + std::vector command_positions = {0, 0, 0, 0, 0, 0}; + std::vector command_velocities = {0, 0, 0, 0, 0, 0}; + + double state_pos_[6] = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; + std::string device_ = ""; + + std::unordered_map> joint_interfaces = { + {"position", {}}, {"velocity", {}}, {"torque", {}}, {"volt", {}}}; + + SerialComms arm_comms_; + + }; + +} // namespace arm_interface + +#endif // ARM_INTERFACE__ARM_INTERFACE_HPP_ diff --git a/control_ws/src/lotti_control/hardware/include/lotti_control/diffbot_system.hpp b/control_ws/src/lotti_control/hardware/include/lotti_control/diffbot_system.hpp new file mode 100644 index 0000000..be016a9 --- /dev/null +++ b/control_ws/src/lotti_control/hardware/include/lotti_control/diffbot_system.hpp @@ -0,0 +1,91 @@ +// Copyright 2021 ros2_control Development Team +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LOTTI_CONTROL__DIFFBOT_SYSTEM_HPP_ +#define LOTTI_CONTROL__DIFFBOT_SYSTEM_HPP_ + +#include +#include +#include + +#include "hardware_interface/handle.hpp" +#include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/system_interface.hpp" +#include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "rclcpp/clock.hpp" +#include "rclcpp/duration.hpp" +#include "rclcpp/macros.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include "lotti_control/wheel.hpp" +#include "lotti_control/visibility_control.h" + +namespace diffdrive_lotti{ + class DiffDriveLotti : public hardware_interface::SystemInterface{ + + struct Config{ + std::string left_wheel_name = ""; + std::string right_wheel_name = ""; + int enc_counts_per_rev = 0; + }; + + + public: + RCLCPP_SHARED_PTR_DEFINITIONS(DiffDriveLotti); + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::CallbackReturn on_init( + const hardware_interface::HardwareInfo & info) override; + + DIFFDRIVE_LOTTI_PUBLIC + std::vector export_state_interfaces() override; + + DIFFDRIVE_LOTTI_PUBLIC + std::vector export_command_interfaces() override; + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::CallbackReturn on_configure( + const rclcpp_lifecycle::State & previous_state) override; + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::CallbackReturn on_cleanup( + const rclcpp_lifecycle::State & previous_state) override; + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::CallbackReturn on_activate( + const rclcpp_lifecycle::State & previous_state) override; + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::CallbackReturn on_deactivate( + const rclcpp_lifecycle::State & previous_state) override; + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::return_type read( + const rclcpp::Time & time, const rclcpp::Duration & period) override; + + DIFFDRIVE_LOTTI_PUBLIC + hardware_interface::return_type write( + const rclcpp::Time & time, const rclcpp::Duration & period) override; + + private: + + Config cfg_; + Wheel wheel_l_; + Wheel wheel_r_; + }; + +} // namespace diffdrive_arduino + +#endif // LOTTI_CONTROL__DIFFBOT_SYSTEM_HPP_ \ No newline at end of file diff --git a/control_ws/src/lotti_control/hardware/include/lotti_control/flipper_interface.hpp b/control_ws/src/lotti_control/hardware/include/lotti_control/flipper_interface.hpp new file mode 100644 index 0000000..f8e3d01 --- /dev/null +++ b/control_ws/src/lotti_control/hardware/include/lotti_control/flipper_interface.hpp @@ -0,0 +1,72 @@ +#ifndef FLIPPER_INTERFACE__FLIPPER_INTERFACE_HPP_ +#define FLIPPER_INTERFACE__FLIPPER_INTERFACE_HPP_ + +#include "string" +#include "unordered_map" +#include "vector" + +#include "hardware_interface/handle.hpp" +#include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/system_interface.hpp" +#include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" + +#include "rclcpp/clock.hpp" +#include "rclcpp/duration.hpp" +#include "rclcpp/logger.hpp" +#include "rclcpp/macros.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" + +#include "lotti_control/serial_comms.hpp" + +using hardware_interface::return_type; + +namespace flipper_interface{ + + using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + + class HARDWARE_INTERFACE_PUBLIC FlipperInterface : public hardware_interface::SystemInterface { + + public: + CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; + + std::vector export_state_interfaces() override; + std::vector export_command_interfaces() override; + + hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; + hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override; + + hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; + hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; + + return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override; + return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override; + + protected: + /// The size of this vector is (standard_interfaces_.size() x nr_joints) + std::vector joint_velocities_command_; + std::vector joint_positions_; + + std::string device_ = ""; + + float fr_cmd_ = 0; + float fl_cmd_ = 0; + float rr_cmd_ = 0; + float rl_cmd_ = 0; + + float fr_state_ = 0; + float fl_state_ = 0; + float rr_state_ = 0; + float rl_state_ = 0; + + std::unordered_map> joint_interfaces = { + {"position", {}}, {"velocity", {}}}; + + //SerialComms flipper_comms_; + }; +} // namespace flipper_interface + +#endif // FLIPPER_INTERFACE__FLIPPER_INTERFACE_HPP_ diff --git a/control_ws/src/lotti_control/hardware/include/lotti_control/serial_comms.hpp b/control_ws/src/lotti_control/hardware/include/lotti_control/serial_comms.hpp new file mode 100644 index 0000000..09d358a --- /dev/null +++ b/control_ws/src/lotti_control/hardware/include/lotti_control/serial_comms.hpp @@ -0,0 +1,80 @@ +#ifndef LOTTI_CONTROL_SERIAL_COMMS_HPP +#define LOTTI_CONTROL_SERIAL_COMMS_HPP + +#include +#include +#include +#include "libserial/SerialPort.h" +#include +#include "sstream" + + +class SerialComms{ + + public: + + SerialComms() = default; + + void connect(const std::string &serial_device){ + timeout_ms_ = 1000; + serial_conn_.Open(serial_device); + serial_conn_.SetBaudRate(LibSerial::BaudRate::BAUD_115200); + } + + + void disconnect(){ + serial_conn_.Close(); + } + + + bool connected() const{ + return serial_conn_.IsOpen(); + } + + + void send_msg(const std::string &msg_to_send){ + serial_conn_.FlushIOBuffers(); // Just in case + serial_conn_.Write(msg_to_send); + } + + + void send_empty_msg(){ + send_msg("\n"); + } + + + std::string read_msg(){ + std::string response = ""; + + try{ + serial_conn_.ReadLine(response, '\n'); + } + catch (const LibSerial::ReadTimeout&){ + std::cerr << "The ReadByte() call has timed out." << std::endl ; + } + return response; + } + + + void set_arm_values(std::vector pos, std::vector vel){ + std::stringstream ss; + for (size_t i = 0; i < pos.size(); i++){ + ss << pos[i] << ":" << vel[i] << "/"; + } + ss << "\n"; + send_msg(ss.str()); + } + + void set_flipper_values(int FR, int FL, int RR, int RL){ + std::stringstream ss; + ss << "FL" << FL << "FR" << FR << "RL" << RL << "RR" << RR << "\n"; + send_msg(ss.str()); + } + + + private: + LibSerial::SerialPort serial_conn_; + int timeout_ms_; +}; + +#endif // LOTTI_CONTROL_SERIAL_COMMS_HPP \ No newline at end of file diff --git a/control_ws/src/lotti_control/hardware/include/lotti_control/visibility_control.h b/control_ws/src/lotti_control/hardware/include/lotti_control/visibility_control.h new file mode 100644 index 0000000..1f8626a --- /dev/null +++ b/control_ws/src/lotti_control/hardware/include/lotti_control/visibility_control.h @@ -0,0 +1,56 @@ +// Copyright 2021 ros2_control Development Team +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/* This header must be included by all rclcpp headers which declare symbols + * which are defined in the rclcpp library. When not building the rclcpp + * library, i.e. when using the headers in other package's code, the contents + * of this header change the visibility of certain symbols which the rclcpp + * library cannot have, but the consuming code must have inorder to link. + */ + +#ifndef LOTTI_CONTROL__VISIBILITY_CONTROL_H_ +#define LOTTI_CONTROL__VISIBILITY_CONTROL_H_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ +#ifdef __GNUC__ +#define DIFFDRIVE_LOTTI_EXPORT __attribute__((dllexport)) +#define DIFFDRIVE_LOTTI_IMPORT __attribute__((dllimport)) +#else +#define DIFFDRIVE_LOTTI_EXPORT __declspec(dllexport) +#define DIFFDRIVE_LOTTI_IMPORT __declspec(dllimport) +#endif +#ifdef DIFFDRIVE_LOTTI_BUILDING_DLL +#define DIFFDRIVE_LOTTI_PUBLIC DIFFDRIVE_LOTTI_EXPORT +#else +#define DIFFDRIVE_LOTTI_PUBLIC DIFFDRIVE_LOTTI_IMPORT +#endif +#define DIFFDRIVE_LOTTI_PUBLIC_TYPE DIFFDRIVE_LOTTI_PUBLIC +#define DIFFDRIVE_LOTTI_LOCAL +#else +#define DIFFDRIVE_LOTTI_EXPORT __attribute__((visibility("default"))) +#define DIFFDRIVE_LOTTI_IMPORT +#if __GNUC__ >= 4 +#define DIFFDRIVE_LOTTI_PUBLIC __attribute__((visibility("default"))) +#define DIFFDRIVE_LOTTI_LOCAL __attribute__((visibility("hidden"))) +#else +#define DIFFDRIVE_LOTTI_PUBLIC +#define DIFFDRIVE_LOTTI_LOCAL +#endif +#define DIFFDRIVE_LOTTI_PUBLIC_TYPE +#endif + +#endif // LOTTI_CONTROL__VISIBILITY_CONTROL_H_ \ No newline at end of file diff --git a/control_ws/src/lotti_control/hardware/include/lotti_control/wheel.hpp b/control_ws/src/lotti_control/hardware/include/lotti_control/wheel.hpp new file mode 100644 index 0000000..8260af7 --- /dev/null +++ b/control_ws/src/lotti_control/hardware/include/lotti_control/wheel.hpp @@ -0,0 +1,31 @@ +#ifndef DIFFDRIVE_LOTTI_WHEEL_HPP +#define DIFFDRIVE_LOTTI_WHEEL_HPP + +#include +#include + + +class Wheel{ + + public: + std::string name = ""; + int enc = 0; + double cmd = 0; + double pos = 0; + double vel = 0; + double rads_per_count = 0; + + Wheel() = default; + + Wheel(const std::string &wheel_name, int counts_per_rev){ + setup(wheel_name, counts_per_rev); + } + + void setup(const std::string &wheel_name, int counts_per_rev){ + name = wheel_name; + rads_per_count = (2*M_PI)/counts_per_rev; + } + +}; + +#endif // DIFFDRIVE_LOTTI_WHEEL_HPP \ No newline at end of file diff --git a/control_ws/src/lotti_control/lotti_control.xml b/control_ws/src/lotti_control/lotti_control.xml new file mode 100644 index 0000000..1a0cb70 --- /dev/null +++ b/control_ws/src/lotti_control/lotti_control.xml @@ -0,0 +1,27 @@ + + + + + Interface to drive Lotti's robot arm + + + + + + Interface to drive Lotti's flippers + + + + + + Interface to drive Lotti's chains + + + + diff --git a/control_ws/src/lotti_control/package.xml b/control_ws/src/lotti_control/package.xml new file mode 100644 index 0000000..c1282a1 --- /dev/null +++ b/control_ws/src/lotti_control/package.xml @@ -0,0 +1,50 @@ + + + + lotti_control + 0.0.0 + Lotti robot control + + Res.Q Bots Austria + + Apache-2.0 + + ament_cmake + + backward_ros + control_msgs + controller_interface + hardware_interface + kdl_parser + pluginlib + rclcpp_lifecycle + rclcpp + rcpputils + realtime_tools + std_msgs + libserial-dev + + + + controller_manager + joint_state_broadcaster + joint_state_publisher_gui + launch_ros + launch + robot_state_publisher + ros2controlcli + ros2launch + rviz2 + urdf + xacro + + ament_cmake_pytest + controller_manager + launch_testing_ros + liburdfdom-tools + xacro + + + ament_cmake + + diff --git a/control_ws/src/lotti_control/test/test_lotti_controller_launch.py b/control_ws/src/lotti_control/test/test_lotti_controller_launch.py new file mode 100644 index 0000000..e1fe0cd --- /dev/null +++ b/control_ws/src/lotti_control/test/test_lotti_controller_launch.py @@ -0,0 +1,104 @@ +# Copyright (c) 2024 AIT - Austrian Institute of Technology GmbH +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the {copyright_holder} nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Christoph Froehlich + +import os +import pytest +import unittest + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_testing.actions import ReadyToTest + +import launch_testing.markers +import rclpy +from controller_manager.test_utils import ( + check_controllers_running, + check_if_js_published, + check_node_running, +) + + +# Executes the given launch file and checks if all nodes can be started +@pytest.mark.rostest +def generate_test_description(): + launch_include = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join( + get_package_share_directory("lotti_control"), + "launch/lotti_controller.launch.py", + ) + ), + launch_arguments={"gui": "false"}.items(), + ) + + return LaunchDescription([launch_include, ReadyToTest()]) + + +# This is our test fixture. Each method is a test case. +# These run alongside the processes specified in generate_test_description() +class TestFixture(unittest.TestCase): + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self): + self.node = rclpy.create_node("test_node") + + def tearDown(self): + self.node.destroy_node() + + def test_node_start(self, proc_output): + check_node_running(self.node, "robot_state_publisher") + + def test_controller_running(self, proc_output): + + cnames = ["lotti_controller", "joint_state_broadcaster"] + + check_controllers_running(self.node, cnames) + + def test_check_if_msgs_published(self): + check_if_js_published( + "/joint_states", ["joint_1", "joint_2", "joint_3", "joint_4", "joint_5", "joint_6"] + ) + + +@launch_testing.post_shutdown_test() +# These tests are run after the processes in generate_test_description() have shutdown. +class TestDescriptionCraneShutdown(unittest.TestCase): + + def test_exit_codes(self, proc_info): + """Check if the processes exited normally.""" + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/control_ws/src/lotti_control/test/test_urdf_xacro.py b/control_ws/src/lotti_control/test/test_urdf_xacro.py new file mode 100644 index 0000000..dabc98a --- /dev/null +++ b/control_ws/src/lotti_control/test/test_urdf_xacro.py @@ -0,0 +1,77 @@ +# Copyright (c) 2022 FZI Forschungszentrum Informatik +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the {copyright_holder} nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Lukas Sackewitz + +import os +import shutil +import subprocess +import tempfile + +from ament_index_python.packages import get_package_share_directory + + +def test_urdf_xacro(): + # General Arguments + description_package = "lotti_control" + description_file = "lotti_main.urdf.xacro" + + description_file_path = os.path.join( + get_package_share_directory(description_package), "urdf", description_file + ) + + (_, tmp_urdf_output_file) = tempfile.mkstemp(suffix=".urdf") + + # Compose `xacro` and `check_urdf` command + xacro_command = ( + f"{shutil.which('xacro')}" f" {description_file_path}" f" > {tmp_urdf_output_file}" + ) + check_urdf_command = f"{shutil.which('check_urdf')} {tmp_urdf_output_file}" + + # Try to call processes but finally remove the temp file + try: + xacro_process = subprocess.run( + xacro_command, stdout=subprocess.PIPE, stderr=subprocess.PIPE, shell=True + ) + + assert xacro_process.returncode == 0, " --- XACRO command failed ---" + + check_urdf_process = subprocess.run( + check_urdf_command, stdout=subprocess.PIPE, stderr=subprocess.PIPE, shell=True + ) + + assert ( + check_urdf_process.returncode == 0 + ), "\n --- URDF check failed! --- \nYour xacro does not unfold into a proper urdf robot description. Please check your xacro file." + + finally: + os.remove(tmp_urdf_output_file) + + +if __name__ == "__main__": + test_urdf_xacro() diff --git a/control_ws/src/lotti_control/test/test_view_robot_launch.py b/control_ws/src/lotti_control/test/test_view_robot_launch.py new file mode 100644 index 0000000..8fc991a --- /dev/null +++ b/control_ws/src/lotti_control/test/test_view_robot_launch.py @@ -0,0 +1,54 @@ +# Copyright (c) 2022 FZI Forschungszentrum Informatik +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the {copyright_holder} nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Lukas Sackewitz + +import os +import pytest + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_testing.actions import ReadyToTest + + +# Executes the given launch file and checks if all nodes can be started +@pytest.mark.rostest +def generate_test_description(): + launch_include = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join( + get_package_share_directory("lotti_control"), + "launch/view_lotti.launch.py", + ) + ), + launch_arguments={"gui": "true"}.items(), + ) + + return LaunchDescription([launch_include, ReadyToTest()]) diff --git a/control_ws/src/lotti_flipper_controller/.vscode/c_cpp_properties.json b/control_ws/src/lotti_flipper_controller/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..4039bef --- /dev/null +++ b/control_ws/src/lotti_flipper_controller/.vscode/c_cpp_properties.json @@ -0,0 +1,16 @@ +{ + "configurations": [ + { + "name": "Linux", + "includePath": [ + "${workspaceFolder}/**" + ], + "defines": [], + "compilerPath": "/usr/bin/gcc", + "cStandard": "c17", + "cppStandard": "gnu++17", + "intelliSenseMode": "linux-gcc-x64" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/control_ws/src/lotti_flipper_controller/CMakeLists.txt b/control_ws/src/lotti_flipper_controller/CMakeLists.txt new file mode 100644 index 0000000..3365bfc --- /dev/null +++ b/control_ws/src/lotti_flipper_controller/CMakeLists.txt @@ -0,0 +1,77 @@ +cmake_minimum_required(VERSION 3.8) +project(lotti_flipper_controller) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# set the same behavior for windows as it is on linux +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + +# find dependencies +set(CONTROLLER_INCLUDE_DEPENDS + pluginlib + rcpputils + controller_interface + realtime_tools + std_msgs + rclcpp +) + +# find dependencies +find_package(backward_ros REQUIRED) +find_package(ament_cmake REQUIRED) +foreach(Dependency IN ITEMS ${CONTROLLER_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() + + +#compile +add_library( + lotti_flipper_controller + SHARED + lotti_flipper_controller/flipper_controller.cpp +) + +target_compile_features(lotti_flipper_controller PUBLIC cxx_std_17) +target_include_directories(lotti_flipper_controller PUBLIC +$ +$ +) +ament_target_dependencies( + lotti_flipper_controller PUBLIC + ${CONTROLLER_INCLUDE_DEPENDS} +) + +# Export controller plugins +pluginlib_export_plugin_description_file(controller_interface lotti_flipper_controller.xml) + +# INSTALL +install( + DIRECTORY lotti_flipper_controller/include/ + DESTINATION include/lotti_flipper_controller +) +install(TARGETS lotti_flipper_controller + EXPORT export_lotti_flipper_controller + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +## EXPORTS +ament_export_targets(export_lotti_flipper_controller HAS_LIBRARY_TARGET) +ament_export_dependencies(${CONTROLLER_INCLUDE_DEPENDS}) +ament_package() + diff --git a/botlaunch/LICENSE b/control_ws/src/lotti_flipper_controller/LICENSE similarity index 100% rename from botlaunch/LICENSE rename to control_ws/src/lotti_flipper_controller/LICENSE diff --git a/control_ws/src/lotti_flipper_controller/lotti_flipper_controller.xml b/control_ws/src/lotti_flipper_controller/lotti_flipper_controller.xml new file mode 100644 index 0000000..0d60b69 --- /dev/null +++ b/control_ws/src/lotti_flipper_controller/lotti_flipper_controller.xml @@ -0,0 +1,10 @@ + + + + Robot controller plugin for Lotti flippers + + + + diff --git a/control_ws/src/lotti_flipper_controller/lotti_flipper_controller/flipper_controller.cpp b/control_ws/src/lotti_flipper_controller/lotti_flipper_controller/flipper_controller.cpp new file mode 100644 index 0000000..b5c01b2 --- /dev/null +++ b/control_ws/src/lotti_flipper_controller/lotti_flipper_controller/flipper_controller.cpp @@ -0,0 +1,143 @@ +#include "lotti_flipper_controller/flipper_controller.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include "rclcpp/qos.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include + + +using config_type = controller_interface::interface_configuration_type; + +namespace flipper_controller{ + FlipperController::FlipperController() : controller_interface::ControllerInterface() {} + + controller_interface::CallbackReturn FlipperController::on_init(){ + // should have error handling + joint_names_ = auto_declare>("joints", joint_names_); + command_interface_types_ = + auto_declare>("command_interfaces", command_interface_types_); + state_interface_types_ = + auto_declare>("state_interfaces", state_interface_types_); + + return CallbackReturn::SUCCESS; + } + + controller_interface::InterfaceConfiguration FlipperController::command_interface_configuration() + const{ + controller_interface::InterfaceConfiguration conf = {config_type::INDIVIDUAL, {}}; + + conf.names.reserve(joint_names_.size() * command_interface_types_.size()); + for (const auto &joint_name : joint_names_){ + for (const auto &interface_type : command_interface_types_){ + conf.names.push_back(joint_name + "/" + interface_type); + } + } + + return conf; + } + + controller_interface::InterfaceConfiguration FlipperController::state_interface_configuration() const{ + controller_interface::InterfaceConfiguration conf = {config_type::INDIVIDUAL, {}}; + + conf.names.reserve(joint_names_.size() * state_interface_types_.size()); + for (const auto &joint_name : joint_names_){ + for (const auto &interface_type : state_interface_types_){ + conf.names.push_back(joint_name + "/" + interface_type); + } + } + + return conf; + } + + controller_interface::CallbackReturn FlipperController::on_configure(const rclcpp_lifecycle::State &){ + auto fr_flipper_callback = + [this](std_msgs::msg::Int8 fr_flipper_msg) -> void { + fr_flipper_cmd = fr_flipper_msg.data; + }; + + auto fl_flipper_callback = + [this](std_msgs::msg::Int8 fl_flipper_msg) -> void { + fl_flipper_cmd = fl_flipper_msg.data; + }; + + auto rr_flipper_callback = + [this](std_msgs::msg::Int8 rr_flipper_msg) -> void { + rr_flipper_cmd = rr_flipper_msg.data; + }; + + auto rl_flipper_callback = + [this](std_msgs::msg::Int8 rl_flipper_msg) -> void { + rl_flipper_cmd = rl_flipper_msg.data; + }; + + // Subscribers + fr_flipper_sub_ = + get_node()->create_subscription( + "/cmd/flipper_fr", 1, fr_flipper_callback); + + fl_flipper_sub_ = + get_node()->create_subscription( + "/cmd/flipper_fl", 1, fl_flipper_callback); + + rr_flipper_sub_ = + get_node()->create_subscription( + "/cmd/flipper_rr", 1, rr_flipper_callback); + + rl_flipper_sub_ = + get_node()->create_subscription( + "/cmd/flipper_rl", 1, rl_flipper_callback); + + return CallbackReturn::SUCCESS; + } + + controller_interface::CallbackReturn FlipperController::on_activate(const rclcpp_lifecycle::State &){ + // clear out vectors in case of restart + joint_velocity_command_interface_.clear(); + joint_position_state_interface_.clear(); + + // assign command interfaces + for (auto & interface : command_interfaces_){ + command_interface_map_[interface.get_interface_name()]->push_back(interface); + } + + // assign state interfaces + for (auto & interface : state_interfaces_){ + state_interface_map_[interface.get_interface_name()]->push_back(interface); + } + + return CallbackReturn::SUCCESS; + } + + controller_interface::return_type FlipperController::update( + const rclcpp::Time & time, const rclcpp::Duration & /*period*/){ + + joint_velocity_command_interface_[1].get().set_value(fr_flipper_cmd); + joint_velocity_command_interface_[0].get().set_value(fl_flipper_cmd); + joint_velocity_command_interface_[3].get().set_value(rr_flipper_cmd); + joint_velocity_command_interface_[2].get().set_value(rl_flipper_cmd); + + //std::cout << std::to_string(fr_flipper_cmd) << "\n"; + return controller_interface::return_type::OK; + } + + controller_interface::CallbackReturn FlipperController::on_deactivate(const rclcpp_lifecycle::State &){ + release_interfaces(); + + return CallbackReturn::SUCCESS; + } + +} // namespace flipper_controller + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + flipper_controller::FlipperController, controller_interface::ControllerInterface) diff --git a/control_ws/src/lotti_flipper_controller/lotti_flipper_controller/include/lotti_flipper_controller/flipper_controller.hpp b/control_ws/src/lotti_flipper_controller/lotti_flipper_controller/include/lotti_flipper_controller/flipper_controller.hpp new file mode 100644 index 0000000..a56e5a2 --- /dev/null +++ b/control_ws/src/lotti_flipper_controller/lotti_flipper_controller/include/lotti_flipper_controller/flipper_controller.hpp @@ -0,0 +1,84 @@ +#ifndef LOTTI_FLIPPER_CONTROLLER__FLIPPER_CONTROLLER_HPP_ +#define LOTTI_FLIPPER_CONTROLLER__FLIPPER_CONTROLLER_HPP_ + +#include +#include +//#include +#include +#include +#include +#include + +//#include "control_msgs/action/follow_joint_trajectory.hpp" +//#include "control_msgs/msg/joint_trajectory_controller_state.hpp" +#include "controller_interface/controller_interface.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/duration.hpp" +#include "rclcpp/subscription.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp/timer.hpp" +#include "rclcpp_lifecycle/lifecycle_publisher.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "realtime_tools/realtime_buffer.hpp" +#include "std_msgs/msg/int8.hpp" + + +namespace flipper_controller{ + class FlipperController : public controller_interface::ControllerInterface{ + public: + FlipperController(); + + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + + controller_interface::return_type update( + const rclcpp::Time & time, const rclcpp::Duration & period) override; + + controller_interface::CallbackReturn on_init() override; + + controller_interface::CallbackReturn on_configure( + const rclcpp_lifecycle::State & previous_state) override; + + controller_interface::CallbackReturn on_activate( + const rclcpp_lifecycle::State & previous_state) override; + + controller_interface::CallbackReturn on_deactivate( + const rclcpp_lifecycle::State & previous_state) override; + + + + protected: + std::vector joint_names_; + std::vector command_interface_types_; + std::vector state_interface_types_; + + rclcpp::Subscription::SharedPtr fr_flipper_sub_; + rclcpp::Subscription::SharedPtr fl_flipper_sub_; + rclcpp::Subscription::SharedPtr rr_flipper_sub_; + rclcpp::Subscription::SharedPtr rl_flipper_sub_; + rclcpp::Time start_time_; + int fr_flipper_cmd = 0; + int fl_flipper_cmd = 0; + int rr_flipper_cmd = 0; + int rl_flipper_cmd = 0; + + std::vector> + joint_velocity_command_interface_; + std::vector> + joint_position_state_interface_; + + std::unordered_map< + std::string, std::vector> *> + command_interface_map_ = { + {"velocity", &joint_velocity_command_interface_}}; + + std::unordered_map< + std::string, std::vector> *> + state_interface_map_ = { + {"position", &joint_position_state_interface_}}; + }; + +} // namespace flipper_controller + +#endif // LOTTI_FLIPPER_CONTROLLER__FLIPPER_CONTROLLER_HPP_ diff --git a/control_ws/src/lotti_flipper_controller/package.xml b/control_ws/src/lotti_flipper_controller/package.xml new file mode 100644 index 0000000..c185a79 --- /dev/null +++ b/control_ws/src/lotti_flipper_controller/package.xml @@ -0,0 +1,43 @@ + + + + lotti_flipper_controller + 0.0.0 + TODO: Package description + paul + Apache-2.0 + + ament_cmake + + backward_ros + control_msgs + controller_interface + kdl_parser + pluginlib + rclcpp_lifecycle + rclcpp + rcpputils + realtime_tools + std_msgs + + controller_manager + launch_ros + launch + ros2controlcli + ros2launch + rviz2 + urdf + xacro + + ament_cmake_pytest + controller_manager + launch_testing_ros + liburdfdom-tools + xacro + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/control_ws/src/lotti_moveit_config/.setup_assistant b/control_ws/src/lotti_moveit_config/.setup_assistant new file mode 100644 index 0000000..1abd522 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/.setup_assistant @@ -0,0 +1,27 @@ +moveit_setup_assistant_config: + urdf: + package: lotti_control + relative_path: description/urdf/Lotti.urdf.xacro + srdf: + relative_path: config/Lotti.srdf + package_settings: + author_name: Res.Q Bots + author_email: office@campus-robo.at + generated_timestamp: 1749479533 + control_xacro: + command: + - position + - velocity + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + - velocity + state: + - position + - velocity \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/CMakeLists.txt b/control_ws/src/lotti_moveit_config/CMakeLists.txt new file mode 100644 index 0000000..4b4802b --- /dev/null +++ b/control_ws/src/lotti_moveit_config/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.22) +project(lotti_moveit_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/launch") + install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +endif() + +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/control_ws/src/lotti_moveit_config/config/Lotti.ros2_control.xacro b/control_ws/src/lotti_moveit_config/config/Lotti.ros2_control.xacro new file mode 100644 index 0000000..1b802f1 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/Lotti.ros2_control.xacro @@ -0,0 +1,62 @@ + + + + + + + + + mock_components/GenericSystem + + + + + + ${initial_positions['arm_link1_joint']} + + + + + + + + ${initial_positions['arm_link2_joint']} + + + + + + + + ${initial_positions['arm_link3_joint']} + + + + + + + + ${initial_positions['arm_link4_joint']} + + + + + + + + ${initial_positions['arm_link5_joint']} + + + + + + + + ${initial_positions['arm_link6_joint']} + + + + + + + diff --git a/control_ws/src/lotti_moveit_config/config/Lotti.srdf b/control_ws/src/lotti_moveit_config/config/Lotti.srdf new file mode 100644 index 0000000..7a39ebe --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/Lotti.srdf @@ -0,0 +1,58 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control_ws/src/lotti_moveit_config/config/Lotti.urdf.xacro b/control_ws/src/lotti_moveit_config/config/Lotti.urdf.xacro new file mode 100644 index 0000000..ab19fc3 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/Lotti.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/control_ws/src/lotti_moveit_config/config/initial_positions.yaml b/control_ws/src/lotti_moveit_config/config/initial_positions.yaml new file mode 100644 index 0000000..dc6e5d9 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/initial_positions.yaml @@ -0,0 +1,9 @@ +# Default initial positions for Lotti's ros2_control fake system + +initial_positions: + arm_link1_joint: 0 + arm_link2_joint: 0 + arm_link3_joint: 0 + arm_link4_joint: 0 + arm_link5_joint: 0 + arm_link6_joint: 0 \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/config/joint_limits.yaml b/control_ws/src/lotti_moveit_config/config/joint_limits.yaml new file mode 100644 index 0000000..e8c225b --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + arm_link1_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + arm_link2_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + arm_link3_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + arm_link4_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + arm_link5_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 + arm_link6_joint: + has_velocity_limits: true + max_velocity: 2 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/config/kinematics.yaml b/control_ws/src/lotti_moveit_config/config/kinematics.yaml new file mode 100644 index 0000000..61c71de --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +lotti_arm_group: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/config/moveit.rviz b/control_ws/src/lotti_moveit_config/config/moveit.rviz new file mode 100644 index 0000000..deb3adb --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: body_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: body_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/control_ws/src/lotti_moveit_config/config/moveit_controllers.yaml b/control_ws/src/lotti_moveit_config/config/moveit_controllers.yaml new file mode 100644 index 0000000..213304c --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/moveit_controllers.yaml @@ -0,0 +1,17 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - arm_controller + + arm_controller: + type: FollowJointTrajectory + joints: + - arm_link1_joint + - arm_link2_joint + - arm_link3_joint + - arm_link4_joint + - arm_link5_joint + - arm_link6_joint \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/config/pilz_cartesian_limits.yaml b/control_ws/src/lotti_moveit_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..b2997ca --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/control_ws/src/lotti_moveit_config/config/ros2_controllers.yaml b/control_ws/src/lotti_moveit_config/config/ros2_controllers.yaml new file mode 100644 index 0000000..abae722 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/ros2_controllers.yaml @@ -0,0 +1,27 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + arm_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +arm_controller: + ros__parameters: + joints: + - arm_link1_joint + - arm_link2_joint + - arm_link3_joint + - arm_link4_joint + - arm_link5_joint + - arm_link6_joint + command_interfaces: + - position + - velocity + state_interfaces: + - position + - velocity \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/config/sensors_3d.yaml b/control_ws/src/lotti_moveit_config/config/sensors_3d.yaml new file mode 100644 index 0000000..99dcaeb --- /dev/null +++ b/control_ws/src/lotti_moveit_config/config/sensors_3d.yaml @@ -0,0 +1,25 @@ +sensors: + - default_sensor + - kinect_depthimage +default_sensor: + far_clipping_plane_distance: 5.0 + filtered_cloud_topic: filtered_cloud + image_topic: /head_mount_kinect/depth_registered/image_raw + max_update_rate: 1.0 + near_clipping_plane_distance: 0.3 + padding_offset: 0.03 + padding_scale: 4.0 + queue_size: 5 + sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater + shadow_threshold: 0.2 +kinect_depthimage: + far_clipping_plane_distance: 5.0 + filtered_cloud_topic: filtered_cloud + image_topic: /head_mount_kinect/depth_registered/image_raw + max_update_rate: 1.0 + near_clipping_plane_distance: 0.3 + padding_offset: 0.03 + padding_scale: 4.0 + queue_size: 5 + sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater + shadow_threshold: 0.2 \ No newline at end of file diff --git a/control_ws/src/lotti_moveit_config/launch/demo.launch.py b/control_ws/src/lotti_moveit_config/launch/demo.launch.py new file mode 100644 index 0000000..03c8b79 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/move_group.launch.py b/control_ws/src/lotti_moveit_config/launch/move_group.launch.py new file mode 100644 index 0000000..ad13aa5 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/moveit_rviz.launch.py b/control_ws/src/lotti_moveit_config/launch/moveit_rviz.launch.py new file mode 100644 index 0000000..03fe747 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/rsp.launch.py b/control_ws/src/lotti_moveit_config/launch/rsp.launch.py new file mode 100644 index 0000000..4e28278 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/setup_assistant.launch.py b/control_ws/src/lotti_moveit_config/launch/setup_assistant.launch.py new file mode 100644 index 0000000..558ad95 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/spawn_controllers.launch.py b/control_ws/src/lotti_moveit_config/launch/spawn_controllers.launch.py new file mode 100644 index 0000000..b552d1d --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/static_virtual_joint_tfs.launch.py b/control_ws/src/lotti_moveit_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 0000000..69e099f --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/launch/warehouse_db.launch.py b/control_ws/src/lotti_moveit_config/launch/warehouse_db.launch.py new file mode 100644 index 0000000..9de9cf3 --- /dev/null +++ b/control_ws/src/lotti_moveit_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("Lotti", package_name="lotti_moveit_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/control_ws/src/lotti_moveit_config/package.xml b/control_ws/src/lotti_moveit_config/package.xml new file mode 100644 index 0000000..02cf0ec --- /dev/null +++ b/control_ws/src/lotti_moveit_config/package.xml @@ -0,0 +1,52 @@ + + + + lotti_moveit_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the Lotti with the MoveIt Motion Planning Framework + + Res.Q Bots + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Res.Q Bots + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + controller_manager + lotti_control + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/control_ws/src/lotti_teleop/LICENSE b/control_ws/src/lotti_teleop/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/control_ws/src/lotti_teleop/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/control_ws/src/lotti_teleop/launch/teleop_launch.py b/control_ws/src/lotti_teleop/launch/teleop_launch.py new file mode 100644 index 0000000..35d08dd --- /dev/null +++ b/control_ws/src/lotti_teleop/launch/teleop_launch.py @@ -0,0 +1,13 @@ +from launch import LaunchDescription +from launch_ros.actions import Node + +def generate_launch_description(): + return LaunchDescription([ + Node( + package='lotti_teleop', + executable='teleop', + output='screen', + name='teleop', + arguments=['--ros-args', '--log-level', 'info'], + ), + ]) \ No newline at end of file diff --git a/chain_controller/chain_controller/__init__.py b/control_ws/src/lotti_teleop/lotti_teleop/__init__.py similarity index 100% rename from chain_controller/chain_controller/__init__.py rename to control_ws/src/lotti_teleop/lotti_teleop/__init__.py diff --git a/control_ws/src/lotti_teleop/lotti_teleop/__pycache__/__init__.cpython-310.pyc b/control_ws/src/lotti_teleop/lotti_teleop/__pycache__/__init__.cpython-310.pyc new file mode 100644 index 0000000..08aa1f2 Binary files /dev/null and b/control_ws/src/lotti_teleop/lotti_teleop/__pycache__/__init__.cpython-310.pyc differ diff --git a/control_ws/src/lotti_teleop/lotti_teleop/__pycache__/lotti_teleop.cpython-310.pyc b/control_ws/src/lotti_teleop/lotti_teleop/__pycache__/lotti_teleop.cpython-310.pyc new file mode 100644 index 0000000..e779dc5 Binary files /dev/null and b/control_ws/src/lotti_teleop/lotti_teleop/__pycache__/lotti_teleop.cpython-310.pyc differ diff --git a/control_ws/src/lotti_teleop/lotti_teleop/lotti_teleop.py b/control_ws/src/lotti_teleop/lotti_teleop/lotti_teleop.py new file mode 100644 index 0000000..2aaa198 --- /dev/null +++ b/control_ws/src/lotti_teleop/lotti_teleop/lotti_teleop.py @@ -0,0 +1,514 @@ +import rclpy +from rclpy.node import Node +import time + +from sensor_msgs.msg import Joy +from geometry_msgs.msg import Twist +from geometry_msgs.msg import TwistStamped +from control_msgs.msg import JointJog +from std_msgs.msg import Int8 +from threading import Lock +from std_srvs.srv import Trigger + + +# Global Defines -------------------------------------------------------------- +# mapping controller buttons and sticks to joy topc axes and buttons + +#axes +left_stick_x = 0 +left_stick_y = 1 +right_stick_x = 3 +right_stick_y = 4 +left_trigger = 2 +right_trigger = 5 +d_pad_x = 6 +d_pad_y = 7 +#buttons +a_button = 0 +b_button = 1 +x_button = 2 +y_button = 3 +lb_button = 4 +rb_button = 5 +opt_left_button = 6 +opt_right_button = 7 +xBox_button = 8 +left_stick_button = 9 +right_stick_button = 10 +space_button = 11 + +PI=3.1415926535897 + +# Class ----------------------------------------------------------------------- +class TeleOp(Node): + + def __init__(self): + #Entrypoint of the class + super().__init__('tele_op') + + #define variables + + #axes + self.__left_stick_x = float(0) + self.__left_stick_x_lock = Lock() + self.__left_stick_y = float(0) + self.__left_stick_y_lock = Lock() + + self.__left_trigger = float(0) + self.__left_trigger_lock = Lock() + + self.__right_stick_x = float(0) + self.__right_stick_x_lock = Lock() + self.__right_stick_y = float(0) + self.__right_stick_y_lock = Lock() + + self.__right_trigger = float(0) + self.__right_trigger_lock = Lock() + + self.__d_pad_x = float(0) + self.__d_pad_x_lock = Lock() + + self.__d_pad_y = float(0) + self.__d_pad_y_lock = Lock() + + #buttons + self.__button_a = int(0) + self.__button_a_lock = Lock() + self.__button_b = int(0) + self.__button_b_lock = Lock() + self.__button_x = int(0) + self.__button_x_lock = Lock() + self.__button_y = int(0) + self.__button_y_lock = Lock() + + self.__button_rb = int(0) + self.__button_rb_lock = Lock() + + self.__button_lb = int(0) + self.__button_lb_lock = Lock() + + self.__button_opt_right = int(0) + self.__button_opt_right_lock = Lock() + + self.__button_opt_left = int(0) + self.__button_opt_left_lock = Lock() + + self.__button_space = int(0) + self.__button_space_lock = Lock() + + + #safety stuff + self.__first_joy_msg_received = bool(False) + self.__joy_enabled = bool(False) + self.__joy_enabled_old = bool(False) + self.__button_opt_right_pressed = bool(False) + self.__button_opt_right_last_pressed = 0.0 + + #switch to arm + self.__arm_enabled = bool(False) + self.__arm_enabled_old = bool(True) + self.__button_opt_left_pressed = bool(False) + self.__button_opt_left_last_pressed = 0.0 + + #flipper controlls + self.__flipper_direction = int + self.__flipper_cmd_fr = Int8() + self.__flipper_cmd_fl = Int8() + self.__flipper_cmd_rr = Int8() + self.__flipper_cmd_rl = Int8() + + #chain controlls + self.__chain_msg = Twist() + self.__chain_msg.linear.y = float(0) + self.__chain_msg.linear.z = float(0) + self.__chain_msg.angular.y = float(0) + self.__chain_msg.angular.x = float(0) + + #arm controlls + self.__arm_msg = TwistStamped() + self.__arm_msg.header.frame_id = "" + + #gripper controlls + self.__gripper_msg = JointJog() + self.__gripper_msg.joint_names = ["arm_link4_joint", "arm_link5_joint", "arm_link6_joint"] + self.__gripper_msg.duration = 0.05 + + #Init class ->create subscriber, create timer + self.__readParams() + self.__callServo() + self.__createSubscribers() + self.__createPublishers() + self.__createTimer() + + self.get_logger().info("Tele_OP initiated") + + + + def __readParams(self): + #declare parameters + self.declare_parameter('Publish_rate', 20) #[Hz] + + #read parameters + self.__Publish_rate = rclpy.parameter.Parameter( + 'Publish_rate', + rclpy.Parameter.Type.DOUBLE, + 20.0 + ) + + + + #the servo_node service needs to be called to start + def __callServo(self): + self.__cli = self.create_client(Trigger, '/servo_node/start_servo') + while not self.__cli.wait_for_service(timeout_sec=1.0): + self.get_logger().info('service not available, waiting again...') + self.__future = self.__cli.call_async(Trigger.Request()) + rclpy.spin_until_future_complete(self, self.__future) + return self.__future.result() + + + + def __checkCMDOutputEnable(self): + + # ----- Enable button check ----- + # If there was no joy msg received before and the twist output somehow is ENABLED, DISABLE the twist output. + if (self.__first_joy_msg_received == False and self.__joy_enabled != False): + self.__joy_enabled = False + + elif (self.__first_joy_msg_received == True): + # If the output is disabled, the output-enable button was not pressed and is now pressed, set the button + # pressed var to true and save the time point when it was pressed to get the time difference. + if(self.__joy_enabled == False and self.__button_opt_right_pressed == False and self.__button_opt_right == 1): + self.__button_opt_right_pressed = True + self.__button_opt_right_last_pressed = time.time() + + # check if button is pressed long enough. + elif (self.__joy_enabled == False and self.__button_opt_right_pressed == True and self.__button_opt_right == 1): + # messure how long the start button is pressed + time_difference = time.time() - self.__button_opt_right_last_pressed + + # If the start button is pressed long enough, enable the controlles + if(time_difference > 1): + self.__joy_enabled = True + + # After the output was enabled, wait for the button to be released befor the button_pressed var is set to false. + elif (self.__joy_enabled == True and self.__button_opt_right_pressed == True and self.__button_opt_right == 0): + self.__button_opt_right_pressed = False + + # if joy is disabled and the start_button was pressed but is released before the output could be + # enabled, the button_pressed var is set to false to receive a new button press. + elif (self.__joy_enabled == False and self.__button_opt_right_pressed == True and self.__button_opt_right == 0): + self.__button_opt_right_pressed = False + + #if joy is enabled and the enable button is pressed, disable the output. + elif (self.__joy_enabled == True and self.__button_opt_right_pressed == False and self.__button_opt_right == 1): + self.__joy_enabled = False + + + # Print a message to show the current output status. + if self.__joy_enabled != self.__joy_enabled_old: + if (self.__joy_enabled == True and self.__joy_enabled_old == False): + self.get_logger().info("Tele Op: ENABLED") + else: + if (self.__joy_enabled == False and self.__joy_enabled_old == True): + self.get_logger().info("Tele Op: DISABLED") + + # Set the old state to the new state + self.__joy_enabled_old = self.__joy_enabled + + + + def __checkArmMode(self): + + # ----- Enable button check ----- + # If there was no joy msg received before and the arm mode is ENABLED, DISABLE it. + if (self.__first_joy_msg_received == False and self.__arm_enabled != False): + self.__arm_enabled = False + + elif (self.__first_joy_msg_received == True): + #if current mode equals old mode and button is newly pressed, start timer + if (self.__arm_enabled != self.__arm_enabled_old and self.__button_opt_left == 1 and self.__button_opt_left_pressed == False): + self.__button_opt_left_pressed = True + self.__button_opt_left_last_pressed = time.time() + + #if timer has been started before + elif (self.__arm_enabled != self.__arm_enabled_old and self.__button_opt_left == 1 and self.__button_opt_left_pressed == True): + # messure how long the start button has been pressed + time_difference = time.time() - self.__button_opt_left_last_pressed + # If the start button has been pressed long enough, switch mode + if (time_difference > 1): + self.__arm_enabled = not self.__arm_enabled + if (self.__arm_enabled == True): + + self.get_logger().info("Control Mode: ARM") + else: + self.get_logger().info("Control Mode: BODY") + + #if mode has been switched, wait until start button is released, then change old mode status to enable new switch cycle + elif (self.__arm_enabled == self.__arm_enabled_old and self.__button_opt_left_pressed == True and self.__button_opt_left == 0): + self.__button_opt_left_pressed = False + self.__arm_enabled_old = not self.__arm_enabled_old + + # if button is not pressed long enough, reset + elif (self.__arm_enabled != self.__arm_enabled_old and self.__button_opt_left_pressed == True and self.__button_opt_left == 0): + self.__button_opt_left_pressed = False + + + + def __calcAndSendFlippers(self): + + if (self.__button_rb == 1 and self.__button_lb == 0): + self.__flipper_direction = 1 + elif(self.__button_rb == 0 and self.__button_lb == 1): + self.__flipper_direction = -1 + else: + self.__flipper_direction = 0 + + if(self.__arm_enabled == False): + self.__flipper_cmd_fr.data = self.__button_y * self.__flipper_direction + self.__flipper_cmd_fl.data = self.__button_x * self.__flipper_direction + self.__flipper_cmd_rr.data = self.__button_b * self.__flipper_direction + self.__flipper_cmd_rl.data = self.__button_a * self.__flipper_direction + else: + self.__flipper_cmd_fr.data = 0 + self.__flipper_cmd_fl.data = 0 + self.__flipper_cmd_rr.data = 0 + self.__flipper_cmd_rl.data = 0 + + + #send the commands + if (self.__joy_enabled == True): + self.__flipper_publisher_fr.publish(self.__flipper_cmd_fr) + self.__flipper_publisher_fl.publish(self.__flipper_cmd_fl) + self.__flipper_publisher_rr.publish(self.__flipper_cmd_rr) + self.__flipper_publisher_rl.publish(self.__flipper_cmd_rl) + + + + def __calcAndSendChains(self): + + #check for arm mode and construct messages to be sent + if(self.__arm_enabled == False): + self.__chain_msg.linear.x = self.__left_stick_y + self.__chain_msg.angular.z = self.__left_stick_x + else: + self.__chain_msg.linear.x = 0.0 + self.__chain_msg.angular.z = 0.0 + + #send movement commands + if (self.__joy_enabled == True): + self.__chain_publisher.publish(self.__chain_msg) + + + + def __calc_and_send_arm(self): + + #calc arm tilt + tilt = abs((self.__right_trigger -1)/2) + (self.__left_trigger -1)/2 + + #calc gripper movement + #gripper_mode = float(self.__button_a - self.__button_b) + gripper_spin = float(self.__button_rb - self.__button_lb) + + #check for arm mode + if(self.__arm_enabled == True): + #construct arm message + self.__arm_msg.twist.linear.x = self.__left_stick_y + self.__arm_msg.twist.linear.y = self.__d_pad_x + self.__arm_msg.twist.linear.z = self.__d_pad_y + self.__arm_msg.twist.angular.z = self.__left_stick_x + self.__arm_msg.twist.angular.y = tilt + self.__arm_msg.twist.angular.x = 0.0 + + #construct gripper message + #self.__gripper_msg.linear.x = gripper_mode + self.__gripper_msg.velocities = [self.__right_stick_y, self.__right_stick_x, gripper_spin] + + else: + self.__arm_msg.twist.linear.x = 0.0 + self.__arm_msg.twist.linear.y = 0.0 + self.__arm_msg.twist.linear.z = 0.0 + self.__arm_msg.twist.angular.z = 0.0 + self.__arm_msg.twist.angular.y = 0.0 + self.__arm_msg.twist.angular.x = 0.0 + + self.__gripper_msg.velocities = [0.0, 0.0, 0.0] + + #add time stamps and seq number + self.__gripper_msg.header.stamp = self.get_clock().now().to_msg() + self.__arm_msg.header.stamp = self.get_clock().now().to_msg() + + #send arm commands + if (self.__joy_enabled == True): + self.__arm_publisher.publish(self.__arm_msg) + self.__gripper_publisher.publish(self.__gripper_msg) + + + + def __timerCallback(self): + self.__checkCMDOutputEnable() + self.__checkArmMode() + self.__calcAndSendFlippers() + self.__calcAndSendChains() + self.__calc_and_send_arm() + + + + def __joyCallback(self, msg): + #save controller input to local variables + + #axes + self.__left_stick_x_lock.acquire() + self.__left_stick_x = msg.axes[left_stick_x] + self.__left_stick_x_lock.release() + + self.__left_stick_y_lock.acquire() + self.__left_stick_y = msg.axes[left_stick_y] + self.__left_stick_y_lock.release() + + self.__left_trigger_lock.acquire() + self.__left_trigger = msg.axes[left_trigger] + self.__left_trigger_lock.release() + + self.__right_stick_x_lock.acquire() + self.__right_stick_x = msg.axes[right_stick_x] + self.__right_stick_x_lock.release() + + self.__right_stick_y_lock.acquire() + self.__right_stick_y = msg.axes[right_stick_y] + self.__right_stick_y_lock.release() + + self.__right_trigger_lock.acquire() + self.__right_trigger = msg.axes[right_trigger] + self.__right_trigger_lock.release() + + self.__d_pad_y_lock.acquire() + self.__d_pad_y = msg.axes[d_pad_y] + self.__d_pad_y_lock.release() + + self.__d_pad_x_lock.acquire() + self.__d_pad_x = msg.axes[d_pad_x] + self.__d_pad_x_lock.release() + + #buttons + self.__button_x_lock.acquire() + self.__button_x = msg.buttons[x_button] + self.__button_x_lock.release() + + self.__button_y_lock.acquire() + self.__button_y = msg.buttons[y_button] + self.__button_y_lock.release() + + self.__button_a_lock.acquire() + self.__button_a = msg.buttons[a_button] + self.__button_a_lock.release() + + self.__button_b_lock.acquire() + self.__button_b = msg.buttons[b_button] + self.__button_b_lock.release() + + self.__button_lb_lock.acquire() + self.__button_lb = msg.buttons[lb_button] + self.__button_lb_lock.release() + + self.__button_rb_lock.acquire() + self.__button_rb = msg.buttons[rb_button] + self.__button_rb_lock.release() + + self.__button_opt_right_lock.acquire() + self.__button_opt_right = msg.buttons[opt_right_button] + self.__button_opt_right_lock.release() + + self.__button_opt_left_lock.acquire() + self.__button_opt_left = msg.buttons[opt_left_button] + self.__button_opt_left_lock.release() + + self.__button_space_lock.acquire() + self.__button_space = msg.buttons[space_button] + self.__button_space_lock.release() + + + # Check if there was a joy msgs since the node was started + if(self.__first_joy_msg_received == False): + self.__first_joy_msg_received = True + + + def __createSubscribers(self): + # Create subscribers + + self._joy_sub = self.create_subscription( + Joy, + 'joy', + self.__joyCallback, + 5, + ) + + def __createPublishers(self): + # Create publishers + + self.__chain_publisher = self.create_publisher( + Twist, + 'chain_controller/cmd_vel_unstamped', + 1 + ) + + self.__flipper_publisher_fr = self.create_publisher( + Int8, + 'cmd/flipper_fr', + 1 + ) + + self.__flipper_publisher_fl = self.create_publisher( + Int8, + 'cmd/flipper_fl', + 1 + ) + + self.__flipper_publisher_rr = self.create_publisher( + Int8, + 'cmd/flipper_rr', + 1 + ) + + self.__flipper_publisher_rl = self.create_publisher( + Int8, + 'cmd/flipper_rl', + 1 + ) + + self.__arm_publisher = self.create_publisher( + TwistStamped, + "cmd/arm/joy_twiststamped", + 1 + ) + + self.__gripper_publisher = self.create_publisher( + JointJog, + "cmd/arm/joy_joint", + 1 + ) + + def __createTimer(self): + # Create timer + self._timer = self.create_timer( + 1.0 / self.__Publish_rate.value, + self.__timerCallback + ) + + +def main(args=None): + rclpy.init(args=args) + + tele_op = TeleOp() + + rclpy.spin(tele_op) + + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + tele_op.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/chain_controller/package.xml b/control_ws/src/lotti_teleop/package.xml similarity index 66% rename from chain_controller/package.xml rename to control_ws/src/lotti_teleop/package.xml index 738cdb5..49df604 100644 --- a/chain_controller/package.xml +++ b/control_ws/src/lotti_teleop/package.xml @@ -1,19 +1,26 @@ - chain_controller + lotti_teleop 0.0.0 TODO: Package description - resqbots - TODO: License declaration + paul + Apache-2.0 + rclpy time math numpy sensor_msgs + geometry_msgs + control_msgs std_msgs threading + time + ros2launch + launch_ros + launch ament_copyright ament_flake8 diff --git a/chain_controller/resource/chain_controller b/control_ws/src/lotti_teleop/resource/lotti_teleop similarity index 100% rename from chain_controller/resource/chain_controller rename to control_ws/src/lotti_teleop/resource/lotti_teleop diff --git a/control_ws/src/lotti_teleop/setup.cfg b/control_ws/src/lotti_teleop/setup.cfg new file mode 100644 index 0000000..50fd966 --- /dev/null +++ b/control_ws/src/lotti_teleop/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/lotti_teleop +[install] +install_scripts=$base/lib/lotti_teleop diff --git a/botlaunch/setup.py b/control_ws/src/lotti_teleop/setup.py similarity index 68% rename from botlaunch/setup.py rename to control_ws/src/lotti_teleop/setup.py index d9b6446..e19d870 100644 --- a/botlaunch/setup.py +++ b/control_ws/src/lotti_teleop/setup.py @@ -1,8 +1,8 @@ +from setuptools import find_packages, setup import os from glob import glob -from setuptools import find_packages, setup -package_name = 'botlaunch' +package_name = 'lotti_teleop' setup( name=package_name, @@ -12,17 +12,18 @@ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))), + (os.path.join('share', package_name, 'launch/'), glob('launch/*launch.py')), ], install_requires=['setuptools'], zip_safe=True, - maintainer='resqbots', - maintainer_email='office@campus-robo.at', + maintainer='paul', + maintainer_email='73643665+PaulKupka@users.noreply.github.com', description='TODO: Package description', license='Apache-2.0', tests_require=['pytest'], entry_points={ 'console_scripts': [ + 'teleop = lotti_teleop.lotti_teleop:main', ], }, ) diff --git a/chain_controller/test/test_copyright.py b/control_ws/src/lotti_teleop/test/test_copyright.py similarity index 100% rename from chain_controller/test/test_copyright.py rename to control_ws/src/lotti_teleop/test/test_copyright.py diff --git a/chain_controller/test/test_flake8.py b/control_ws/src/lotti_teleop/test/test_flake8.py similarity index 100% rename from chain_controller/test/test_flake8.py rename to control_ws/src/lotti_teleop/test/test_flake8.py diff --git a/chain_controller/test/test_pep257.py b/control_ws/src/lotti_teleop/test/test_pep257.py similarity index 100% rename from chain_controller/test/test_pep257.py rename to control_ws/src/lotti_teleop/test/test_pep257.py diff --git a/get_raspi_map.sh b/get_raspi_map.sh new file mode 100755 index 0000000..17ccf06 --- /dev/null +++ b/get_raspi_map.sh @@ -0,0 +1,2 @@ +#!/bin/bash +scp resqbots@lidarpi.local:/home/resqbots/maps/latest_map.pcd /home/paul/maps/last_raspi_map.pcd diff --git a/kill_process.sh b/kill_process.sh new file mode 100644 index 0000000..f8c33a6 --- /dev/null +++ b/kill_process.sh @@ -0,0 +1,3 @@ +#! /bin/bash +pkill --signal 2 -f "/node name + --ros-args" + diff --git a/old stuff/Lotti_arm.urdf.xacro b/old stuff/Lotti_arm.urdf.xacro new file mode 100644 index 0000000..55116e1 --- /dev/null +++ b/old stuff/Lotti_arm.urdf.xacro @@ -0,0 +1,11 @@ + + + + + + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm.xacro b/old stuff/Lotti_arm.xacro new file mode 100644 index 0000000..adb1945 --- /dev/null +++ b/old stuff/Lotti_arm.xacro @@ -0,0 +1,244 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF3/CMakeLists.txt b/old stuff/Lotti_arm_URDF3/CMakeLists.txt new file mode 100644 index 0000000..783597f --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) + +project(Lotti_arm_URDF3) + +find_package(catkin REQUIRED) + +catkin_package() + +find_package(roslaunch) + +foreach(dir config launch meshes urdf) + install(DIRECTORY ${dir}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) +endforeach(dir) diff --git a/old stuff/Lotti_arm_URDF3/config/joint_names_Lotti_arm_URDF3.yaml b/old stuff/Lotti_arm_URDF3/config/joint_names_Lotti_arm_URDF3.yaml new file mode 100644 index 0000000..a80d700 --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/config/joint_names_Lotti_arm_URDF3.yaml @@ -0,0 +1 @@ +controller_joint_names: ['', 'arm_link1_joint', 'arm_link2_joint', 'arm_link3_joint', 'arm_link4_joint', 'arm_link5_joint', 'arm_link6_joint', ] diff --git a/old stuff/Lotti_arm_URDF3/export.log b/old stuff/Lotti_arm_URDF3/export.log new file mode 100644 index 0000000..699427c --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/export.log @@ -0,0 +1,281 @@ +2025-06-05 17:15:20,163 INFO Logger.cs: 70 - +-------------------------------------------------------------------------------- +2025-06-05 17:15:20,179 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter +2025-06-05 17:15:20,179 INFO Logger.cs: 73 - Commit version 1.6.0-4-g7f85cfe +2025-06-05 17:15:20,179 INFO Logger.cs: 74 - Build version 1.6.7995.38578 +2025-06-05 17:15:20,194 INFO SwAddin.cs: 192 - Attempting to connect to SW +2025-06-05 17:15:20,194 INFO SwAddin.cs: 197 - Setting up callbacks +2025-06-05 17:15:20,194 INFO SwAddin.cs: 201 - Setting up command manager +2025-06-05 17:15:20,194 INFO SwAddin.cs: 204 - Adding command manager +2025-06-05 17:15:20,194 INFO SwAddin.cs: 263 - Adding Assembly export to file menu +2025-06-05 17:15:20,194 INFO SwAddin.cs: 272 - Adding Part export to file menu +2025-06-05 17:15:20,194 INFO SwAddin.cs: 210 - Adding event handlers +2025-06-05 17:15:20,194 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks +2025-06-05 17:25:18,728 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 17:25:23,630 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 17:25:24,564 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 17:25:24,565 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 17:25:24,589 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 17:25:24,590 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 17:25:24,591 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:25:24,592 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:25:24,593 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 17:25:24,594 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:25:24,595 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 17:25:24,596 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 17:25:24,596 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:25:24,597 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 17:25:24,598 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 17:25:24,598 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:25:24,599 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 17:25:24,599 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 17:25:24,600 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:25:24,600 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 17:25:24,601 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 17:25:24,601 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:25:24,602 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 17:25:24,602 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 17:25:24,603 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:25:24,603 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 17:25:24,604 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 17:25:24,604 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:25:24,605 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 17:25:24,605 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 17:25:24,606 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 17:25:24,606 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 17:25:24,607 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:25:24,607 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:25:24,607 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 17:25:24,608 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:25:24,608 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 17:25:24,609 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 17:25:24,609 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:25:24,610 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 17:25:24,610 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 17:25:24,610 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:25:24,613 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 17:25:24,614 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 17:25:24,653 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:25:24,653 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 17:25:24,654 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 17:25:24,654 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:25:24,655 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 17:25:24,655 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 17:25:24,656 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:25:24,657 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 17:25:24,658 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 17:25:24,659 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:25:24,659 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 17:25:26,883 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 17:25:26,899 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration +2025-06-05 17:25:26,899 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 17:25:39,254 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:25:46,635 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:00,609 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:01,076 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:02,009 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:02,708 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:02,877 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:03,026 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:03,676 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:04,149 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:06,625 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:07,225 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:07,572 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:08,843 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:15,181 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:24,917 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:07,415 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:07,787 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:09,180 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:48,928 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:54,067 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:56,059 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:01,717 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:28,844 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:39,879 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:43,180 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:48,949 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:56,701 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:09,603 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:09,888 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:10,252 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:10,675 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:11,720 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:13,289 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:13,520 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:13,757 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:14,772 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:20,172 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:20,739 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:26,224 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:44,764 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:45,091 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:45,651 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:46,029 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:46,586 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:47,972 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:52,118 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:52,852 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:57,117 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:58,419 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:00,387 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:01,603 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:02,203 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:19,439 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:34,667 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:35,429 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:35,697 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:35,997 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:36,297 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:36,714 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:37,530 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:38,998 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:39,501 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:39,715 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:39,946 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:40,186 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:40,555 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:44,162 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:44,901 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:50,648 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 17:32:50,935 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 17:32:51,177 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_base_link to child arm_link1_link failed +2025-06-05 17:32:51,334 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 17:32:51,402 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 17:32:51,635 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 17:32:51,718 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 17:32:52,434 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 17:32:52,504 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link3_link to child arm_link4_link failed +2025-06-05 17:32:53,073 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link5_link +2025-06-05 17:32:53,134 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link4_link to child arm_link5_link failed +2025-06-05 17:32:53,688 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link6_link +2025-06-05 17:32:53,756 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link5_link to child arm_link6_link failed +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1136 - Found 67 in URDF_Assembly.SLDASM +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:32:55,720 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 17:32:55,720 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 67 in URDF_Assembly.SLDASM +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 17:32:55,888 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:41:18,242 INFO AssemblyExportForm.cs: 253 - Completing URDF export +2025-06-05 17:41:18,242 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruearm_base_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link3_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruenametruearm_link6_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 17:41:51,684 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\offic\Desktop\Lotti_arm_URDF3 +2025-06-05 17:41:51,686 INFO ExportHelper.cs: 147 - Beginning the export process +2025-06-05 17:41:51,686 INFO ExportHelper.cs: 153 - Creating package directories with name Lotti_arm_URDF3 and save path C:\Users\offic\Desktop +2025-06-05 17:41:53,334 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at C:\Users\offic\Desktop\Lotti_arm_URDF3\CMakeLists.txt +2025-06-05 17:41:53,334 INFO ExportHelper.cs: 166 - Creating joint names config at C:\Users\offic\Desktop\Lotti_arm_URDF3\config\joint_names_Lotti_arm_URDF3.yaml +2025-06-05 17:41:53,334 INFO ExportHelper.cs: 170 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF3\package.xml +2025-06-05 17:41:53,334 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF3\package.xml +2025-06-05 17:41:53,350 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in C:\Users\offic\Desktop\Lotti_arm_URDF3\launch\ +2025-06-05 17:41:53,353 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in C:\Users\offic\Desktop\Lotti_arm_URDF3\launch\ +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 187 - Saving existing STL preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 450 - Saving users preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 190 - Modifying STL preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 464 - Setting STL preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 196 - Found 0 hidden components +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 197 - Hiding all components +2025-06-05 17:41:53,482 INFO ExportHelper.cs: 204 - Beginning individual files export +2025-06-05 17:41:53,485 INFO ExportHelper.cs: 270 - Exporting link: arm_base_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_base_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link1_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link1_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link2_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link2_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link3_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link3_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link4_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link4_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link5_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link5_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link6_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link6_link has 0 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 317 - arm_link6_link: Exporting STL with coordinate frame hand_spin_system +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 322 - arm_link6_link: Reference geometry name +2025-06-05 17:41:54,304 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link6_link.STL +2025-06-05 17:41:56,335 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:56,335 INFO ExportHelper.cs: 317 - arm_link5_link: Exporting STL with coordinate frame hand_yaw_system +2025-06-05 17:41:56,335 INFO ExportHelper.cs: 322 - arm_link5_link: Reference geometry name +2025-06-05 17:41:56,405 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link5_link.STL +2025-06-05 17:41:57,060 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:57,061 INFO ExportHelper.cs: 317 - arm_link4_link: Exporting STL with coordinate frame hand_pitch_system +2025-06-05 17:41:57,061 INFO ExportHelper.cs: 322 - arm_link4_link: Reference geometry name +2025-06-05 17:41:57,130 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link4_link.STL +2025-06-05 17:41:57,788 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:57,788 INFO ExportHelper.cs: 317 - arm_link3_link: Exporting STL with coordinate frame forearm_system +2025-06-05 17:41:57,788 INFO ExportHelper.cs: 322 - arm_link3_link: Reference geometry name +2025-06-05 17:41:57,854 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link3_link.STL +2025-06-05 17:41:58,666 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:58,666 INFO ExportHelper.cs: 317 - arm_link2_link: Exporting STL with coordinate frame upper_arm_system +2025-06-05 17:41:58,667 INFO ExportHelper.cs: 322 - arm_link2_link: Reference geometry name +2025-06-05 17:41:58,721 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link2_link.STL +2025-06-05 17:41:59,035 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:59,035 INFO ExportHelper.cs: 317 - arm_link1_link: Exporting STL with coordinate frame shoulder_system +2025-06-05 17:41:59,035 INFO ExportHelper.cs: 322 - arm_link1_link: Reference geometry name +2025-06-05 17:41:59,089 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link1_link.STL +2025-06-05 17:41:59,389 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:59,389 INFO ExportHelper.cs: 317 - arm_base_link: Exporting STL with coordinate frame base_system +2025-06-05 17:41:59,389 INFO ExportHelper.cs: 322 - arm_base_link: Reference geometry name +2025-06-05 17:41:59,452 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_base_link.STL +2025-06-05 17:41:59,589 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:59,589 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components +2025-06-05 17:41:59,773 INFO ExportHelper.cs: 145 - Resetting STL preferences +2025-06-05 17:41:59,774 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 17:41:59,775 INFO ExportHelper.cs: 228 - Writing URDF file to C:\Users\offic\Desktop\Lotti_arm_URDF3\urdf\Lotti_arm_URDF3.urdf +2025-06-05 17:41:59,780 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\offic\Desktop\Lotti_arm_URDF3\urdf\Lotti_arm_URDF3.csv +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,804 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,804 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,804 INFO ExportHelper.cs: 234 - Copying log file +2025-06-05 17:41:59,804 INFO ExportHelper.cs: 439 - Copying C:\Users\offic\sw2urdf_logs\sw2urdf.log to C:\Users\offic\Desktop\Lotti_arm_URDF3\export.log diff --git a/old stuff/Lotti_arm_URDF3/launch/display.launch b/old stuff/Lotti_arm_URDF3/launch/display.launch new file mode 100644 index 0000000..2582787 --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/launch/display.launch @@ -0,0 +1,20 @@ + + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF3/launch/gazebo.launch b/old stuff/Lotti_arm_URDF3/launch/gazebo.launch new file mode 100644 index 0000000..fbfbd4e --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/launch/gazebo.launch @@ -0,0 +1,20 @@ + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_base_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_base_link.STL new file mode 100644 index 0000000..de736dc Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_base_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_link1_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_link1_link.STL new file mode 100644 index 0000000..343c61a Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_link1_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_link2_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_link2_link.STL new file mode 100644 index 0000000..20d3e2c Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_link2_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_link3_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_link3_link.STL new file mode 100644 index 0000000..afb4b9c Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_link3_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_link4_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_link4_link.STL new file mode 100644 index 0000000..ec8bb3d Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_link4_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_link5_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_link5_link.STL new file mode 100644 index 0000000..34e183b Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_link5_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/meshes/arm_link6_link.STL b/old stuff/Lotti_arm_URDF3/meshes/arm_link6_link.STL new file mode 100644 index 0000000..a75551c Binary files /dev/null and b/old stuff/Lotti_arm_URDF3/meshes/arm_link6_link.STL differ diff --git a/old stuff/Lotti_arm_URDF3/package.xml b/old stuff/Lotti_arm_URDF3/package.xml new file mode 100644 index 0000000..4663e6b --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/package.xml @@ -0,0 +1,21 @@ + + Lotti_arm_URDF3 + 1.0.0 + +

URDF Description package for Lotti_arm_URDF3

+

This package contains configuration data, 3D models and launch files +for Lotti_arm_URDF3 robot

+
+ TODO + + BSD + catkin + roslaunch + robot_state_publisher + rviz + joint_state_publisher_gui + gazebo + + + +
\ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF3/urdf/Lotti_arm_URDF3.csv b/old stuff/Lotti_arm_URDF3/urdf/Lotti_arm_URDF3.csv new file mode 100644 index 0000000..73038b6 --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/urdf/Lotti_arm_URDF3.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +arm_base_link,"-0,00263222915365037","-0,000332098550481226","0,0476250352231148",0,0,0,"0,200226640012258","0,00030515518623871","5,91937552347525E-09","-5,48255039093506E-06","0,000183595401496948","3,03172951951874E-10","0,000356726067861412",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_base_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_base_link.STL,,URDF_basis-1,base_system,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +arm_link1_link,"4,4154208761471E-09","0,000122631739122251","0,0356096098271416",0,0,0,"0,227235996796303","0,000180809625442164","1,99972159386555E-12","3,65735412272402E-13","0,000141436764733896","-1,12077733619126E-07","0,000174149091246638",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link1_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link1_link.STL,,URDF_schulter-1,shoulder_system,Achse8,arm_link1_joint,revolute,0,0,"0,0813",0,0,"1,5708",arm_base_link,0,0,-1,3,2,-3,3,,,,,,,, +arm_link2_link,"-0,00485070166931217","0,000134479355761746","0,151153269049843",0,0,0,"0,308407355142343","0,000536262443976751","-5,5940179993781E-07","4,55969735855309E-05","0,000463619869555736","-5,41211706294873E-05","0,00028846239166877",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link2_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link2_link.STL,,URDF_oberarm-1,upper_arm_system,Achse9,arm_link2_joint,revolute,0,"0,002","0,093",0,"1,4835","-1,5708",arm_link1_link,0,1,0,3,2,"-1,5","1,5",,,,,,,, +arm_link3_link,"-2,34730375641701E-05","0,000222724116049157","0,121657320094858",0,0,0,"0,215223683624819","0,000187887481718193","1,29568722040541E-09","-2,48383575759204E-09","0,000177005795528886","-1,95381298527238E-05","5,96362197609908E-05",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link3_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link3_link.STL,,URDF_unterarm-1,forearm_system,Achse10,arm_link3_joint,revolute,"-0,05",0,"0,29",0,"-0,087266",0,arm_link2_link,0,1,0,3,2,-3,0,,,,,,,, +arm_link4_link,"-6,45090288222683E-05","-2,78077069245375E-05","0,0421410408275518",0,0,0,"0,0799976203193007","2,98275167277768E-05","-3,78870865349402E-10","2,42643938146629E-10","1,60577540866642E-05","1,06831058124357E-09","2,00421216012606E-05",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link4_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link4_link.STL,,URDF_hand_kipp-1,hand_pitch_system,Achse11,arm_link4_joint,revolute,0,"0,0006","0,26473",0,0,0,arm_link3_link,0,-1,0,3,2,"-1,5","1,5",,,,,,,, +arm_link5_link,"0,00382150605784096","-7,85621768924008E-05","0,0340017507140255",0,0,0,"0,0824183861074866","1,34651970301421E-05","1,06510176553104E-09","7,33151583062687E-09","3,06523685609496E-05","3,77177397811794E-10","3,09091303833254E-05",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link5_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link5_link.STL,,URDF_hand_dreh-1,hand_yaw_system,Achse12,arm_link5_joint,revolute,"-0,00055","0,0001","0,074331",0,0,0,arm_link4_link,1,0,0,3,2,"-1,5","1,5",,,,,,,, +arm_link6_link,"0,0143574958730077","0,0022820490393657","0,0446512981778615",0,0,0,"0,110464975833809","3,80573356318663E-05","-6,92148846739205E-08","-1,61451005762783E-06","2,62917054320985E-05","7,3462765439727E-09","1,59336336306215E-05",0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link6_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF3/meshes/arm_link6_link.STL,,URDF_Greifer-1,hand_spin_system,Achse13,arm_link6_joint,revolute,"0,022033",0,"0,0668",0,0,0,arm_link5_link,0,0,1,3,2,-3,3,,,,,,,, diff --git a/old stuff/Lotti_arm_URDF3/urdf/Lotti_arm_URDF3.urdf b/old stuff/Lotti_arm_URDF3/urdf/Lotti_arm_URDF3.urdf new file mode 100644 index 0000000..d304956 --- /dev/null +++ b/old stuff/Lotti_arm_URDF3/urdf/Lotti_arm_URDF3.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF4/CMakeLists.txt b/old stuff/Lotti_arm_URDF4/CMakeLists.txt new file mode 100644 index 0000000..fac732f --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) + +project(Lotti_arm_URDF4) + +find_package(catkin REQUIRED) + +catkin_package() + +find_package(roslaunch) + +foreach(dir config launch meshes urdf) + install(DIRECTORY ${dir}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) +endforeach(dir) diff --git a/old stuff/Lotti_arm_URDF4/config/joint_names_Lotti_arm_URDF4.yaml b/old stuff/Lotti_arm_URDF4/config/joint_names_Lotti_arm_URDF4.yaml new file mode 100644 index 0000000..a80d700 --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/config/joint_names_Lotti_arm_URDF4.yaml @@ -0,0 +1 @@ +controller_joint_names: ['', 'arm_link1_joint', 'arm_link2_joint', 'arm_link3_joint', 'arm_link4_joint', 'arm_link5_joint', 'arm_link6_joint', ] diff --git a/old stuff/Lotti_arm_URDF4/export.log b/old stuff/Lotti_arm_URDF4/export.log new file mode 100644 index 0000000..cd4cfde --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/export.log @@ -0,0 +1,826 @@ +2025-06-05 17:15:20,163 INFO Logger.cs: 70 - +-------------------------------------------------------------------------------- +2025-06-05 17:15:20,179 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter +2025-06-05 17:15:20,179 INFO Logger.cs: 73 - Commit version 1.6.0-4-g7f85cfe +2025-06-05 17:15:20,179 INFO Logger.cs: 74 - Build version 1.6.7995.38578 +2025-06-05 17:15:20,194 INFO SwAddin.cs: 192 - Attempting to connect to SW +2025-06-05 17:15:20,194 INFO SwAddin.cs: 197 - Setting up callbacks +2025-06-05 17:15:20,194 INFO SwAddin.cs: 201 - Setting up command manager +2025-06-05 17:15:20,194 INFO SwAddin.cs: 204 - Adding command manager +2025-06-05 17:15:20,194 INFO SwAddin.cs: 263 - Adding Assembly export to file menu +2025-06-05 17:15:20,194 INFO SwAddin.cs: 272 - Adding Part export to file menu +2025-06-05 17:15:20,194 INFO SwAddin.cs: 210 - Adding event handlers +2025-06-05 17:15:20,194 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks +2025-06-05 17:25:18,728 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 17:25:23,630 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 17:25:24,564 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 17:25:24,565 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 17:25:24,589 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 17:25:24,590 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 17:25:24,591 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:25:24,592 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:25:24,593 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 17:25:24,594 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:25:24,595 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 17:25:24,596 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 17:25:24,596 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:25:24,597 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 17:25:24,598 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 17:25:24,598 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:25:24,599 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 17:25:24,599 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 17:25:24,600 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:25:24,600 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 17:25:24,601 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 17:25:24,601 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:25:24,602 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 17:25:24,602 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 17:25:24,603 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:25:24,603 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 17:25:24,604 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 17:25:24,604 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:25:24,605 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 17:25:24,605 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 17:25:24,606 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 17:25:24,606 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 17:25:24,607 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:25:24,607 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:25:24,607 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 17:25:24,608 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:25:24,608 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 17:25:24,609 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 17:25:24,609 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:25:24,610 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 17:25:24,610 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 17:25:24,610 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:25:24,613 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 17:25:24,614 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 17:25:24,653 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:25:24,653 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 17:25:24,654 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 17:25:24,654 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:25:24,655 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 17:25:24,655 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 17:25:24,656 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:25:24,657 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 17:25:24,658 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 17:25:24,659 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:25:24,659 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 17:25:26,883 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 17:25:26,899 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration +2025-06-05 17:25:26,899 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 17:25:39,254 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:25:46,635 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:00,609 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:01,076 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:02,009 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:02,708 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:02,877 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:03,026 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:03,676 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:04,149 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:06,625 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:07,225 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:07,572 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:08,843 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:15,181 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:26:24,917 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:07,415 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:07,787 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:09,180 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:48,928 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:54,067 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:29:56,059 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:01,717 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:28,844 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:39,879 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:43,180 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:48,949 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:30:56,701 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:09,603 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:09,888 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:10,252 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:10,675 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:11,720 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:13,289 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:13,520 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:13,757 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:14,772 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:20,172 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:20,739 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:26,224 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:44,764 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:45,091 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:45,651 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:46,029 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:46,586 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:47,972 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:52,118 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:52,852 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:57,117 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:31:58,419 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:00,387 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:01,603 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:02,203 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:19,439 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:34,667 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:35,429 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:35,697 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:35,997 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:36,297 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:36,714 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:37,530 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:38,998 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:39,501 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:39,715 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:39,946 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:40,186 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:40,555 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:44,162 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:44,901 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:32:50,648 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 17:32:50,935 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 17:32:51,177 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_base_link to child arm_link1_link failed +2025-06-05 17:32:51,334 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 17:32:51,402 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 17:32:51,635 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 17:32:51,718 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 17:32:52,434 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 17:32:52,504 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link3_link to child arm_link4_link failed +2025-06-05 17:32:53,073 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link5_link +2025-06-05 17:32:53,134 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link4_link to child arm_link5_link failed +2025-06-05 17:32:53,688 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link6_link +2025-06-05 17:32:53,756 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link5_link to child arm_link6_link failed +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1136 - Found 67 in URDF_Assembly.SLDASM +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 17:32:55,705 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:32:55,720 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 17:32:55,720 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 67 in URDF_Assembly.SLDASM +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 17:32:55,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 17:32:55,888 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 17:41:18,242 INFO AssemblyExportForm.cs: 253 - Completing URDF export +2025-06-05 17:41:18,242 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruearm_base_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link3_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruenametruearm_link6_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 17:41:51,684 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\offic\Desktop\Lotti_arm_URDF3 +2025-06-05 17:41:51,686 INFO ExportHelper.cs: 147 - Beginning the export process +2025-06-05 17:41:51,686 INFO ExportHelper.cs: 153 - Creating package directories with name Lotti_arm_URDF3 and save path C:\Users\offic\Desktop +2025-06-05 17:41:53,334 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at C:\Users\offic\Desktop\Lotti_arm_URDF3\CMakeLists.txt +2025-06-05 17:41:53,334 INFO ExportHelper.cs: 166 - Creating joint names config at C:\Users\offic\Desktop\Lotti_arm_URDF3\config\joint_names_Lotti_arm_URDF3.yaml +2025-06-05 17:41:53,334 INFO ExportHelper.cs: 170 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF3\package.xml +2025-06-05 17:41:53,334 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF3\package.xml +2025-06-05 17:41:53,350 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in C:\Users\offic\Desktop\Lotti_arm_URDF3\launch\ +2025-06-05 17:41:53,353 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in C:\Users\offic\Desktop\Lotti_arm_URDF3\launch\ +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 187 - Saving existing STL preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 450 - Saving users preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 190 - Modifying STL preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 464 - Setting STL preferences +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 196 - Found 0 hidden components +2025-06-05 17:41:53,354 INFO ExportHelper.cs: 197 - Hiding all components +2025-06-05 17:41:53,482 INFO ExportHelper.cs: 204 - Beginning individual files export +2025-06-05 17:41:53,485 INFO ExportHelper.cs: 270 - Exporting link: arm_base_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_base_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link1_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link1_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link2_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link2_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link3_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link3_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link4_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link4_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link5_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link5_link has 1 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 270 - Exporting link: arm_link6_link +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 272 - Link arm_link6_link has 0 children +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 317 - arm_link6_link: Exporting STL with coordinate frame hand_spin_system +2025-06-05 17:41:53,486 INFO ExportHelper.cs: 322 - arm_link6_link: Reference geometry name +2025-06-05 17:41:54,304 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link6_link.STL +2025-06-05 17:41:56,335 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:56,335 INFO ExportHelper.cs: 317 - arm_link5_link: Exporting STL with coordinate frame hand_yaw_system +2025-06-05 17:41:56,335 INFO ExportHelper.cs: 322 - arm_link5_link: Reference geometry name +2025-06-05 17:41:56,405 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link5_link.STL +2025-06-05 17:41:57,060 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:57,061 INFO ExportHelper.cs: 317 - arm_link4_link: Exporting STL with coordinate frame hand_pitch_system +2025-06-05 17:41:57,061 INFO ExportHelper.cs: 322 - arm_link4_link: Reference geometry name +2025-06-05 17:41:57,130 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link4_link.STL +2025-06-05 17:41:57,788 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:57,788 INFO ExportHelper.cs: 317 - arm_link3_link: Exporting STL with coordinate frame forearm_system +2025-06-05 17:41:57,788 INFO ExportHelper.cs: 322 - arm_link3_link: Reference geometry name +2025-06-05 17:41:57,854 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link3_link.STL +2025-06-05 17:41:58,666 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:58,666 INFO ExportHelper.cs: 317 - arm_link2_link: Exporting STL with coordinate frame upper_arm_system +2025-06-05 17:41:58,667 INFO ExportHelper.cs: 322 - arm_link2_link: Reference geometry name +2025-06-05 17:41:58,721 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link2_link.STL +2025-06-05 17:41:59,035 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:59,035 INFO ExportHelper.cs: 317 - arm_link1_link: Exporting STL with coordinate frame shoulder_system +2025-06-05 17:41:59,035 INFO ExportHelper.cs: 322 - arm_link1_link: Reference geometry name +2025-06-05 17:41:59,089 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_link1_link.STL +2025-06-05 17:41:59,389 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:59,389 INFO ExportHelper.cs: 317 - arm_base_link: Exporting STL with coordinate frame base_system +2025-06-05 17:41:59,389 INFO ExportHelper.cs: 322 - arm_base_link: Reference geometry name +2025-06-05 17:41:59,452 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF3\meshes\arm_base_link.STL +2025-06-05 17:41:59,589 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 17:41:59,589 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components +2025-06-05 17:41:59,773 INFO ExportHelper.cs: 145 - Resetting STL preferences +2025-06-05 17:41:59,774 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 17:41:59,775 INFO ExportHelper.cs: 228 - Writing URDF file to C:\Users\offic\Desktop\Lotti_arm_URDF3\urdf\Lotti_arm_URDF3.urdf +2025-06-05 17:41:59,780 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\offic\Desktop\Lotti_arm_URDF3\urdf\Lotti_arm_URDF3.csv +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,789 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,804 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,804 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 17:41:59,804 INFO ExportHelper.cs: 234 - Copying log file +2025-06-05 17:41:59,804 INFO ExportHelper.cs: 439 - Copying C:\Users\offic\sw2urdf_logs\sw2urdf.log to C:\Users\offic\Desktop\Lotti_arm_URDF3\export.log +2025-06-05 17:41:59,804 INFO ExportHelper.cs: 237 - Resetting STL preferences +2025-06-05 17:41:59,804 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 18:18:20,133 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 18:18:20,133 INFO SwAddin.cs: 299 - Save is required +2025-06-05 18:18:20,133 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 18:18:21,273 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:18:21,273 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 18:18:21,289 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:18:21,305 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 18:18:23,461 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 18:18:23,461 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration +2025-06-05 18:18:23,461 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 18:19:20,800 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:34,331 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:47,627 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:47,845 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:48,845 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:49,455 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:51,204 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:57,298 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:19:57,845 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:02,672 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:16,421 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:16,593 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:17,249 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:18,749 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:19,030 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:21,749 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:22,015 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:26,046 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:40,826 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:40,998 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:41,138 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:41,763 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:43,560 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:52,012 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:52,731 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:53,122 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:53,872 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:54,169 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:56,403 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:56,637 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:56,840 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:20:59,418 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:00,106 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:00,574 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:20,917 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:27,979 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:42,337 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:42,587 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:42,993 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:46,587 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:48,321 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:48,696 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:49,258 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:49,852 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:52,180 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:52,446 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:21:58,851 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:11,397 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:11,569 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:11,803 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:12,085 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:14,194 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:19,615 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:20,506 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:20,865 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:21,318 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:24,443 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:26,443 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:26,834 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:36,458 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:49,426 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:49,598 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:49,754 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:49,910 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:50,082 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:50,644 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:51,926 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:52,082 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:52,269 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:52,426 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:52,582 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:52,738 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:53,691 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:53,894 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:54,332 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:22:55,769 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:23:27,454 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 18:23:27,673 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 18:23:27,751 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_base_link to child arm_link1_link failed +2025-06-05 18:23:27,907 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 18:23:27,985 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 18:23:28,220 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 18:23:28,298 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 18:23:29,001 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 18:23:29,079 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link3_link to child arm_link4_link failed +2025-06-05 18:23:29,626 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link5_link +2025-06-05 18:23:29,704 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link4_link to child arm_link5_link failed +2025-06-05 18:23:30,251 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link6_link +2025-06-05 18:23:30,313 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link5_link to child arm_link6_link failed +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:23:32,219 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:23:32,251 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:23:32,266 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 18:23:32,391 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:25:12,134 INFO AssemblyExportForm.cs: 253 - Completing URDF export +2025-06-05 18:25:12,134 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruearm_base_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link3_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10Koordinatensystem1linktruenametruearm_link4_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruenametruearm_link6_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 18:25:31,101 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\offic\Desktop\Lotti_arm_URDF4 +2025-06-05 18:25:31,101 INFO ExportHelper.cs: 147 - Beginning the export process +2025-06-05 18:25:31,101 INFO ExportHelper.cs: 153 - Creating package directories with name Lotti_arm_URDF4 and save path C:\Users\offic\Desktop +2025-06-05 18:25:32,695 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at C:\Users\offic\Desktop\Lotti_arm_URDF4\CMakeLists.txt +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 166 - Creating joint names config at C:\Users\offic\Desktop\Lotti_arm_URDF4\config\joint_names_Lotti_arm_URDF4.yaml +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 170 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF4\package.xml +2025-06-05 18:25:32,711 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF4\package.xml +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in C:\Users\offic\Desktop\Lotti_arm_URDF4\launch\ +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in C:\Users\offic\Desktop\Lotti_arm_URDF4\launch\ +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 187 - Saving existing STL preferences +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 450 - Saving users preferences +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 190 - Modifying STL preferences +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 464 - Setting STL preferences +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 196 - Found 0 hidden components +2025-06-05 18:25:32,711 INFO ExportHelper.cs: 197 - Hiding all components +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 204 - Beginning individual files export +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_base_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_base_link has 1 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_link1_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_link1_link has 1 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_link2_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_link2_link has 1 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_link3_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_link3_link has 1 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_link4_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_link4_link has 1 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_link5_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_link5_link has 1 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 270 - Exporting link: arm_link6_link +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 272 - Link arm_link6_link has 0 children +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 317 - arm_link6_link: Exporting STL with coordinate frame hand_spin_system +2025-06-05 18:25:33,101 INFO ExportHelper.cs: 322 - arm_link6_link: Reference geometry name +2025-06-05 18:25:33,882 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link6_link.STL +2025-06-05 18:25:35,742 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:35,742 INFO ExportHelper.cs: 317 - arm_link5_link: Exporting STL with coordinate frame hand_yaw_system +2025-06-05 18:25:35,742 INFO ExportHelper.cs: 322 - arm_link5_link: Reference geometry name +2025-06-05 18:25:35,804 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link5_link.STL +2025-06-05 18:25:36,414 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:36,414 INFO ExportHelper.cs: 317 - arm_link4_link: Exporting STL with coordinate frame hand_pitch_system +2025-06-05 18:25:36,414 INFO ExportHelper.cs: 322 - arm_link4_link: Reference geometry name +2025-06-05 18:25:36,476 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link4_link.STL +2025-06-05 18:25:37,101 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:37,101 INFO ExportHelper.cs: 317 - arm_link3_link: Exporting STL with coordinate frame Koordinatensystem1 +2025-06-05 18:25:37,101 INFO ExportHelper.cs: 322 - arm_link3_link: Reference geometry name +2025-06-05 18:25:37,429 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link3_link.STL +2025-06-05 18:25:38,273 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:38,273 INFO ExportHelper.cs: 317 - arm_link2_link: Exporting STL with coordinate frame upper_arm_system +2025-06-05 18:25:38,273 INFO ExportHelper.cs: 322 - arm_link2_link: Reference geometry name +2025-06-05 18:25:38,335 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link2_link.STL +2025-06-05 18:25:38,632 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:38,632 INFO ExportHelper.cs: 317 - arm_link1_link: Exporting STL with coordinate frame shoulder_system +2025-06-05 18:25:38,632 INFO ExportHelper.cs: 322 - arm_link1_link: Reference geometry name +2025-06-05 18:25:38,695 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link1_link.STL +2025-06-05 18:25:38,976 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:38,976 INFO ExportHelper.cs: 317 - arm_base_link: Exporting STL with coordinate frame base_system +2025-06-05 18:25:38,976 INFO ExportHelper.cs: 322 - arm_base_link: Reference geometry name +2025-06-05 18:25:39,038 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_base_link.STL +2025-06-05 18:25:39,179 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:25:39,179 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 145 - Resetting STL preferences +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 228 - Writing URDF file to C:\Users\offic\Desktop\Lotti_arm_URDF4\urdf\Lotti_arm_URDF4.urdf +2025-06-05 18:25:39,632 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\offic\Desktop\Lotti_arm_URDF4\urdf\Lotti_arm_URDF4.csv +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 234 - Copying log file +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 439 - Copying C:\Users\offic\sw2urdf_logs\sw2urdf.log to C:\Users\offic\Desktop\Lotti_arm_URDF4\export.log +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 237 - Resetting STL preferences +2025-06-05 18:25:39,632 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 18:27:21,365 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 18:27:22,864 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 18:27:23,802 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 18:27:23,802 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 18:27:23,802 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 18:27:23,818 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 18:27:23,818 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:27:23,818 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:27:23,818 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 18:27:23,849 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:27:23,849 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:27:23,864 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:27:23,880 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 18:27:26,036 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 18:27:26,036 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration +2025-06-05 18:27:26,036 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 18:27:34,567 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:43,566 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:56,456 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:57,456 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:58,393 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:58,846 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:59,237 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:27:59,940 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:00,268 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:06,471 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:19,173 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:20,110 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:20,954 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:22,563 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:22,907 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:23,782 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:24,391 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:29,000 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:41,609 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:42,281 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:43,015 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:44,312 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:44,671 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:45,280 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:46,015 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:28:46,499 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:02,029 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:05,857 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:17,450 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:17,997 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:18,309 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:18,715 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:20,934 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:21,309 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:21,934 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:22,809 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:24,809 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:25,121 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:32,839 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:46,713 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:46,901 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:47,151 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:47,385 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:48,198 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:49,166 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:49,682 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:49,947 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:50,447 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:51,307 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:52,010 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:52,354 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:29:57,853 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:09,415 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:09,602 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:09,759 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:09,962 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:10,149 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:10,540 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:11,383 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:11,571 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:11,727 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:11,915 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:12,477 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:12,821 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:13,555 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:14,071 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:30:21,273 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 18:30:21,492 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 18:30:21,555 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_base_link to child arm_link1_link failed +2025-06-05 18:30:21,711 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 18:30:21,773 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 18:30:22,008 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 18:30:22,070 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 18:30:22,758 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 18:30:22,820 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link3_link to child arm_link4_link failed +2025-06-05 18:30:23,383 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link5_link +2025-06-05 18:30:23,445 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link4_link to child arm_link5_link failed +2025-06-05 18:30:23,976 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link6_link +2025-06-05 18:30:24,039 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link5_link to child arm_link6_link failed +2025-06-05 18:30:25,914 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 18:30:25,929 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 66 in URDF_Assembly.SLDASM +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 18:30:25,961 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 18:30:25,976 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 18:30:25,976 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 18:30:25,976 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 18:30:25,976 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 18:30:26,101 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 18:31:55,938 INFO AssemblyExportForm.cs: 253 - Completing URDF export +2025-06-05 18:31:55,938 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruearm_base_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link3_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10Koordinatensystem1linktruenametruearm_link4_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruenametruearm_link6_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 18:32:10,656 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\offic\Desktop\Lotti_arm_URDF4 +2025-06-05 18:32:10,656 INFO ExportHelper.cs: 147 - Beginning the export process +2025-06-05 18:32:10,656 INFO ExportHelper.cs: 153 - Creating package directories with name Lotti_arm_URDF4 and save path C:\Users\offic\Desktop +2025-06-05 18:32:11,828 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at C:\Users\offic\Desktop\Lotti_arm_URDF4\CMakeLists.txt +2025-06-05 18:32:12,000 INFO ExportHelper.cs: 166 - Creating joint names config at C:\Users\offic\Desktop\Lotti_arm_URDF4\config\joint_names_Lotti_arm_URDF4.yaml +2025-06-05 18:32:12,000 INFO ExportHelper.cs: 170 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF4\package.xml +2025-06-05 18:32:12,000 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\offic\Desktop\Lotti_arm_URDF4\package.xml +2025-06-05 18:32:12,000 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in C:\Users\offic\Desktop\Lotti_arm_URDF4\launch\ +2025-06-05 18:32:12,000 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in C:\Users\offic\Desktop\Lotti_arm_URDF4\launch\ +2025-06-05 18:32:12,000 INFO ExportHelper.cs: 187 - Saving existing STL preferences +2025-06-05 18:32:12,000 INFO ExportHelper.cs: 450 - Saving users preferences +2025-06-05 18:32:12,015 INFO ExportHelper.cs: 190 - Modifying STL preferences +2025-06-05 18:32:12,015 INFO ExportHelper.cs: 464 - Setting STL preferences +2025-06-05 18:32:12,015 INFO ExportHelper.cs: 196 - Found 0 hidden components +2025-06-05 18:32:12,015 INFO ExportHelper.cs: 197 - Hiding all components +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 204 - Beginning individual files export +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_base_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_base_link has 1 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_link1_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_link1_link has 1 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_link2_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_link2_link has 1 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_link3_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_link3_link has 1 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_link4_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_link4_link has 1 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_link5_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_link5_link has 1 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 270 - Exporting link: arm_link6_link +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 272 - Link arm_link6_link has 0 children +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 317 - arm_link6_link: Exporting STL with coordinate frame hand_spin_system +2025-06-05 18:32:12,359 INFO ExportHelper.cs: 322 - arm_link6_link: Reference geometry name +2025-06-05 18:32:13,109 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link6_link.STL +2025-06-05 18:32:14,968 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:14,968 INFO ExportHelper.cs: 317 - arm_link5_link: Exporting STL with coordinate frame hand_yaw_system +2025-06-05 18:32:14,968 INFO ExportHelper.cs: 322 - arm_link5_link: Reference geometry name +2025-06-05 18:32:15,046 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link5_link.STL +2025-06-05 18:32:15,656 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:15,656 INFO ExportHelper.cs: 317 - arm_link4_link: Exporting STL with coordinate frame hand_pitch_system +2025-06-05 18:32:15,656 INFO ExportHelper.cs: 322 - arm_link4_link: Reference geometry name +2025-06-05 18:32:15,718 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link4_link.STL +2025-06-05 18:32:16,343 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:16,343 INFO ExportHelper.cs: 317 - arm_link3_link: Exporting STL with coordinate frame Koordinatensystem1 +2025-06-05 18:32:16,343 INFO ExportHelper.cs: 322 - arm_link3_link: Reference geometry name +2025-06-05 18:32:16,640 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link3_link.STL +2025-06-05 18:32:17,437 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:17,437 INFO ExportHelper.cs: 317 - arm_link2_link: Exporting STL with coordinate frame upper_arm_system +2025-06-05 18:32:17,452 INFO ExportHelper.cs: 322 - arm_link2_link: Reference geometry name +2025-06-05 18:32:17,499 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link2_link.STL +2025-06-05 18:32:17,796 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:17,796 INFO ExportHelper.cs: 317 - arm_link1_link: Exporting STL with coordinate frame shoulder_system +2025-06-05 18:32:17,796 INFO ExportHelper.cs: 322 - arm_link1_link: Reference geometry name +2025-06-05 18:32:17,859 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_link1_link.STL +2025-06-05 18:32:18,140 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:18,140 INFO ExportHelper.cs: 317 - arm_base_link: Exporting STL with coordinate frame base_system +2025-06-05 18:32:18,140 INFO ExportHelper.cs: 322 - arm_base_link: Reference geometry name +2025-06-05 18:32:18,187 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\Lotti_arm_URDF4\meshes\arm_base_link.STL +2025-06-05 18:32:18,327 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 18:32:18,327 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components +2025-06-05 18:32:18,718 INFO ExportHelper.cs: 145 - Resetting STL preferences +2025-06-05 18:32:18,718 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 18:32:18,718 INFO ExportHelper.cs: 228 - Writing URDF file to C:\Users\offic\Desktop\Lotti_arm_URDF4\urdf\Lotti_arm_URDF4.urdf +2025-06-05 18:32:18,718 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\offic\Desktop\Lotti_arm_URDF4\urdf\Lotti_arm_URDF4.csv +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 18:32:18,718 INFO ExportHelper.cs: 234 - Copying log file +2025-06-05 18:32:18,718 INFO ExportHelper.cs: 439 - Copying C:\Users\offic\sw2urdf_logs\sw2urdf.log to C:\Users\offic\Desktop\Lotti_arm_URDF4\export.log diff --git a/old stuff/Lotti_arm_URDF4/launch/display.launch b/old stuff/Lotti_arm_URDF4/launch/display.launch new file mode 100644 index 0000000..de663e2 --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/launch/display.launch @@ -0,0 +1,20 @@ + + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF4/launch/gazebo.launch b/old stuff/Lotti_arm_URDF4/launch/gazebo.launch new file mode 100644 index 0000000..241d9b3 --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/launch/gazebo.launch @@ -0,0 +1,20 @@ + + + + + + \ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_base_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_base_link.STL new file mode 100644 index 0000000..de736dc Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_base_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_link1_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_link1_link.STL new file mode 100644 index 0000000..343c61a Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_link1_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_link2_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_link2_link.STL new file mode 100644 index 0000000..20d3e2c Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_link2_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_link3_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_link3_link.STL new file mode 100644 index 0000000..1c1393d Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_link3_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_link4_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_link4_link.STL new file mode 100644 index 0000000..ec8bb3d Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_link4_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_link5_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_link5_link.STL new file mode 100644 index 0000000..2334a3c Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_link5_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/meshes/arm_link6_link.STL b/old stuff/Lotti_arm_URDF4/meshes/arm_link6_link.STL new file mode 100644 index 0000000..1c1edc8 Binary files /dev/null and b/old stuff/Lotti_arm_URDF4/meshes/arm_link6_link.STL differ diff --git a/old stuff/Lotti_arm_URDF4/package.xml b/old stuff/Lotti_arm_URDF4/package.xml new file mode 100644 index 0000000..2f493ae --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/package.xml @@ -0,0 +1,21 @@ + + Lotti_arm_URDF4 + 1.0.0 + +

URDF Description package for Lotti_arm_URDF4

+

This package contains configuration data, 3D models and launch files +for Lotti_arm_URDF4 robot

+
+ TODO + + BSD + catkin + roslaunch + robot_state_publisher + rviz + joint_state_publisher_gui + gazebo + + + +
\ No newline at end of file diff --git a/old stuff/Lotti_arm_URDF4/urdf/Lotti_arm_URDF4.csv b/old stuff/Lotti_arm_URDF4/urdf/Lotti_arm_URDF4.csv new file mode 100644 index 0000000..f22d256 --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/urdf/Lotti_arm_URDF4.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +arm_base_link,"-0,00263222915365038","-0,000332098550481226","0,0476250352231148",0,0,0,"0,200226640012258","0,00030515518623871","5,9193755234795E-09","-5,48255039093506E-06","0,000183595401496948","3,03172951946039E-10","0,000356726067861412",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_base_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_base_link.STL,,URDF_basis-1,base_system,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +arm_link1_link,"4,41542086226931E-09","0,000122631739122248","0,0356096098271416",0,0,0,"0,227235996796303","0,000180809625442164","1,99972159337586E-12","3,65735427518995E-13","0,000141436764733896","-1,12077733619125E-07","0,000174149091246638",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link1_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link1_link.STL,,URDF_schulter-1,shoulder_system,Achse8,arm_link1_joint,revolute,0,0,"0,0813",0,0,"1,5708",arm_base_link,0,0,-1,3,2,-3,3,,,,,,,, +arm_link2_link,"-0,0048507016693122","0,000134479355761746","0,151153269049844",0,0,0,"0,308407355142343","0,000536262443976751","-5,59401799937812E-07","4,55969735855309E-05","0,000463619869555736","-5,41211706294874E-05","0,00028846239166877",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link2_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link2_link.STL,,URDF_oberarm-1,upper_arm_system,Achse9,arm_link2_joint,revolute,0,"0,002","0,093",0,"1,4835","-1,5708",arm_link1_link,0,1,0,3,2,"-1,5","1,5",,,,,,,, +arm_link3_link,"-2,34730375641978E-05","0,000222724116048956","0,121657320094858",0,0,0,"0,215223683624819","0,000187887481718192","1,29568722040644E-09","-2,48383575759051E-09","0,000177005795528886","-1,95381298527238E-05","5,96362197609908E-05",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link3_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link3_link.STL,,URDF_unterarm-1,Koordinatensystem1,Achse10,arm_link3_joint,revolute,"-0,05",0,"0,29","-3,1416","-0,087266","-3,1416",arm_link2_link,0,1,0,3,2,"-1,5","1,5",,,,,,,, +arm_link4_link,"-6,45090288222683E-05","-2,78077069245236E-05","0,0421410408275518",0,0,0,"0,0799976203193007","2,98275167277768E-05","-3,7887086534939E-10","2,42643938146603E-10","1,60577540866642E-05","1,06831058124334E-09","2,00421216012606E-05",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link4_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link4_link.STL,,URDF_hand_kipp-1,hand_pitch_system,Achse11,arm_link4_joint,revolute,0,"0,0006","0,26473",0,0,0,arm_link3_link,0,-1,0,3,2,"-1,5","1,5",,,,,,,, +arm_link5_link,"0,00382150605784218","-7,85621768924077E-05","0,0340017507140268",0,0,0,"0,0824183861074926","1,34651970301422E-05","1,06510176549428E-09","7,33151583060291E-09","3,06523685609497E-05","3,77177397775468E-10","3,09091303833254E-05",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link5_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link5_link.STL,,URDF_hand_dreh-1,hand_yaw_system,Achse12,arm_link5_joint,revolute,"-0,00055","0,0001","0,074331",0,0,0,arm_link4_link,1,0,0,3,2,"-1,5","1,5",,,,,,,, +arm_link6_link,"0,0143574958730443","0,0022820490392805","0,0446512981777231",0,0,0,"0,110464975833159","3,80573356318646E-05","-6,92148846731947E-08","-1,6145100576273E-06","2,62917054320962E-05","7,34627654398345E-09","1,59336336306205E-05",0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link6_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://Lotti_arm_URDF4/meshes/arm_link6_link.STL,,URDF_Greifer-1,hand_spin_system,Achse13,arm_link6_joint,revolute,"0,022033",0,"0,0668",0,0,0,arm_link5_link,0,0,1,3,2,-3,3,,,,,,,, diff --git a/old stuff/Lotti_arm_URDF4/urdf/Lotti_arm_URDF4.urdf b/old stuff/Lotti_arm_URDF4/urdf/Lotti_arm_URDF4.urdf new file mode 100644 index 0000000..f36f006 --- /dev/null +++ b/old stuff/Lotti_arm_URDF4/urdf/Lotti_arm_URDF4.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/old stuff/URDF_arm_URDF2/CMakeLists.txt b/old stuff/URDF_arm_URDF2/CMakeLists.txt new file mode 100644 index 0000000..cdfe0c4 --- /dev/null +++ b/old stuff/URDF_arm_URDF2/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) + +project(URDF_arm_URDF2) + +find_package(catkin REQUIRED) + +catkin_package() + +find_package(roslaunch) + +foreach(dir config launch meshes urdf) + install(DIRECTORY ${dir}/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) +endforeach(dir) diff --git a/old stuff/URDF_arm_URDF2/config/joint_names_URDF_arm_URDF2.yaml b/old stuff/URDF_arm_URDF2/config/joint_names_URDF_arm_URDF2.yaml new file mode 100644 index 0000000..a80d700 --- /dev/null +++ b/old stuff/URDF_arm_URDF2/config/joint_names_URDF_arm_URDF2.yaml @@ -0,0 +1 @@ +controller_joint_names: ['', 'arm_link1_joint', 'arm_link2_joint', 'arm_link3_joint', 'arm_link4_joint', 'arm_link5_joint', 'arm_link6_joint', ] diff --git a/old stuff/URDF_arm_URDF2/export.log b/old stuff/URDF_arm_URDF2/export.log new file mode 100644 index 0000000..fd80898 --- /dev/null +++ b/old stuff/URDF_arm_URDF2/export.log @@ -0,0 +1,574 @@ +2025-06-05 13:54:13,111 INFO Logger.cs: 70 - +-------------------------------------------------------------------------------- +2025-06-05 13:54:13,158 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter +2025-06-05 13:54:13,158 INFO Logger.cs: 73 - Commit version 1.6.0-4-g7f85cfe +2025-06-05 13:54:13,158 INFO Logger.cs: 74 - Build version 1.6.7995.38578 +2025-06-05 13:54:13,158 INFO SwAddin.cs: 192 - Attempting to connect to SW +2025-06-05 13:54:13,158 INFO SwAddin.cs: 197 - Setting up callbacks +2025-06-05 13:54:13,158 INFO SwAddin.cs: 201 - Setting up command manager +2025-06-05 13:54:13,158 INFO SwAddin.cs: 204 - Adding command manager +2025-06-05 13:54:13,158 INFO SwAddin.cs: 263 - Adding Assembly export to file menu +2025-06-05 13:54:13,158 INFO SwAddin.cs: 272 - Adding Part export to file menu +2025-06-05 13:54:13,158 INFO SwAddin.cs: 210 - Adding event handlers +2025-06-05 13:54:13,174 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks +2025-06-05 15:18:44,537 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 15:18:44,537 INFO SwAddin.cs: 305 - A rebuild is required +2025-06-05 15:18:44,537 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 15:18:45,483 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 15:18:45,508 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 15:18:45,514 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:18:45,515 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 15:18:45,515 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:18:45,516 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:18:45,517 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 15:18:45,518 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:18:45,518 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 15:18:45,518 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 15:18:45,519 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:18:45,519 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 15:18:45,520 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 15:18:45,520 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:18:45,522 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 15:18:45,522 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 15:18:45,536 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:18:45,537 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 15:18:45,537 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 15:18:45,538 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:18:45,538 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:18:45,539 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 15:18:47,766 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 15:18:47,772 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruearm_base_linkxyztrue0.00263220.047625-0.0003321rpytrue000originfalsefalsevaluetrue0.20023massfalseixxtrue0.00030516ixytrue5.4826E-06ixztrue-5.9194E-09iyytrue0.00035673iyztrue3.0317E-10izztrue0.0001836inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue-0.000122634.4154E-090.03561rpytrue000originfalsefalsevaluetrue0.22724massfalseixxtrue0.00014144ixytrue-1.9997E-12ixztrue1.1208E-07iyytrue0.00018081iyztrue3.6574E-13izztrue0.00017415inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue00.0810rpytrue-1.570800originfalsefalselinktruearm_base_linkparenttruelinktruearm_link1_linkchildtruexyztrue00-1axisfalselowertrue-2.9uppertrue2.9efforttrue10velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue-0.00485070.000134490.15115rpytrue000originfalsefalsevaluetrue0.30841massfalseixxtrue0.00053626ixytrue-5.5942E-07ixztrue4.5597E-05iyytrue0.00046362iyztrue-5.4121E-05izztrue0.00028846inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000.093rpytrue01.22170originfalsefalselinktruearm_link1_linkparenttruelinktruearm_link2_linkchildtruexyztrue010axisfalselowertrue-2.4uppertrue0.4efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue-2.3473E-050.000222720.12166rpytrue000originfalsefalsevaluetrue0.21522massfalseixxtrue0.00018789ixytrue1.2957E-09ixztrue-2.4838E-09iyytrue0.00017701iyztrue-1.9538E-05izztrue5.9636E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link3_jointtypetruerevolutexyztrue-0.0500.29rpytrue000originfalsefalselinktruearm_link2_linkparenttruelinktruearm_link3_linkchildtruexyztrue010axisfalselowertrue2.7uppertrue0.3efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue-6.4509E-05-2.7808E-050.042141rpytrue000originfalsefalsevaluetrue0.079998massfalseixxtrue2.9828E-05ixytrue-3.7887E-10ixztrue2.4264E-10iyytrue1.6058E-05iyztrue1.0683E-09izztrue2.0042E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000.26473rpytrue000originfalsefalselinktruearm_link3_linkparenttruelinktruearm_link4_linkchildtruexyztrue0-10axisfalselowertrue-1.5uppertrue1.5efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_tilt_systemlinktruenametruearm_link5_linkxyztrue-0.0041786-0.00382150.034002rpytrue000originfalsefalsevaluetrue0.082418massfalseixxtrue3.0652E-05ixytrue-1.0651E-09ixztrue3.7718E-10iyytrue1.3465E-05iyztrue-7.3315E-09izztrue3.0909E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000.074331rpytrue001.5708originfalsefalselinktruearm_link4_linkparenttruelinktruearm_link5_linkchildtruexyztrue0-10axisfalselowertrue-1.5uppertrue1.5efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_twist_systemlinktruenametruearm_link6_linkxyztrue0.0143574958728778790.00228204903910118670.044651298178213145rpytrue000originfalsefalsevaluetrue0.1104649758352941massfalseixxtrue3.8057335631870236E-05ixytrue-6.9214884672569178E-08ixztrue-1.6145100576269089E-06iyytrue2.6291705432102431E-05iyztrue7.3462765424507441E-09izztrue1.5933633630625143E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue-0.004100.0668rpytrue00-1.5708originfalsefalselinktruearm_link5_linkparenttruelinktruearm_link6_linkchildtruexyztrue00-1axisfalselowertrue-3uppertrue3efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 15:18:47,880 INFO LinkNode.cs: 35 - Building node arm_base_link +2025-06-05 15:18:47,880 INFO LinkNode.cs: 35 - Building node arm_link1_link +2025-06-05 15:18:47,880 INFO LinkNode.cs: 35 - Building node arm_link2_link +2025-06-05 15:18:47,881 INFO LinkNode.cs: 35 - Building node arm_link3_link +2025-06-05 15:18:47,881 INFO LinkNode.cs: 35 - Building node arm_link4_link +2025-06-05 15:18:47,881 INFO LinkNode.cs: 35 - Building node arm_link5_link +2025-06-05 15:18:47,882 INFO LinkNode.cs: 35 - Building node arm_link6_link +2025-06-05 15:18:47,883 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_base_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,884 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_basis-1@URDF_Assembly? +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\01_Baugrupppe_Drehkranz\URDF_basis.SLDPRT +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_base_link +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link1_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_schulter-1@URDF_Assembly? +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\01_Baugrupppe_Drehkranz\URDF_schulter.SLDPRT +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link1_link +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link2_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_oberarm-1@URDF_Assembly? +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\02_Baugruppe_Glied_1\URDF_oberarm.SLDPRT +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link2_link +2025-06-05 15:18:47,922 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link3_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_unterarm-1@URDF_Assembly? +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\03_Baugruppe_Glied_2\URDF_unterarm.SLDPRT +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link3_link +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link4_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_hand_kipp-1@URDF_Assembly? +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\04_Baugruppe_Glied_3\URDF_hand_kipp.SLDPRT +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link4_link +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link5_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_hand_dreh-1@URDF_Assembly? +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\05_Baugruppe_Drehung\URDF_hand_dreh.SLDPRT +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link5_link +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link6_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_Greifer-1@URDF_Assembly? +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\06_Baugruppe_Greifer\URDF_Greifer.SLDPRT +2025-06-05 15:18:47,937 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link6_link +2025-06-05 15:18:47,981 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 15:19:05,741 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 15:19:05,761 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruearm_base_linkxyztrue0.00263220.047625-0.0003321rpytrue000originfalsefalsevaluetrue0.20023massfalseixxtrue0.00030516ixytrue5.4826E-06ixztrue-5.9194E-09iyytrue0.00035673iyztrue3.0317E-10izztrue0.0001836inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue-0.000122634.4154E-090.03561rpytrue000originfalsefalsevaluetrue0.22724massfalseixxtrue0.00014144ixytrue-1.9997E-12ixztrue1.1208E-07iyytrue0.00018081iyztrue3.6574E-13izztrue0.00017415inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue00.0810rpytrue-1.570800originfalsefalselinktruearm_base_linkparenttruelinktruearm_link1_linkchildtruexyztrue00-1axisfalselowertrue-2.9uppertrue2.9efforttrue10velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue-0.00485070.000134490.15115rpytrue000originfalsefalsevaluetrue0.30841massfalseixxtrue0.00053626ixytrue-5.5942E-07ixztrue4.5597E-05iyytrue0.00046362iyztrue-5.4121E-05izztrue0.00028846inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000.093rpytrue01.22170originfalsefalselinktruearm_link1_linkparenttruelinktruearm_link2_linkchildtruexyztrue010axisfalselowertrue-2.4uppertrue0.4efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue-2.3473E-050.000222720.12166rpytrue000originfalsefalsevaluetrue0.21522massfalseixxtrue0.00018789ixytrue1.2957E-09ixztrue-2.4838E-09iyytrue0.00017701iyztrue-1.9538E-05izztrue5.9636E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link3_jointtypetruerevolutexyztrue-0.0500.29rpytrue000originfalsefalselinktruearm_link2_linkparenttruelinktruearm_link3_linkchildtruexyztrue010axisfalselowertrue2.7uppertrue0.3efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue-6.4509E-05-2.7808E-050.042141rpytrue000originfalsefalsevaluetrue0.079998massfalseixxtrue2.9828E-05ixytrue-3.7887E-10ixztrue2.4264E-10iyytrue1.6058E-05iyztrue1.0683E-09izztrue2.0042E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000.26473rpytrue000originfalsefalselinktruearm_link3_linkparenttruelinktruearm_link4_linkchildtruexyztrue0-10axisfalselowertrue-1.5uppertrue1.5efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_tilt_systemlinktruenametruearm_link5_linkxyztrue-0.0041786-0.00382150.034002rpytrue000originfalsefalsevaluetrue0.082418massfalseixxtrue3.0652E-05ixytrue-1.0651E-09ixztrue3.7718E-10iyytrue1.3465E-05iyztrue-7.3315E-09izztrue3.0909E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000.074331rpytrue001.5708originfalsefalselinktruearm_link4_linkparenttruelinktruearm_link5_linkchildtruexyztrue0-10axisfalselowertrue-1.5uppertrue1.5efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_twist_systemlinktruenametruearm_link6_linkxyztrue0.0143574958728778790.00228204903910118670.044651298178213145rpytrue000originfalsefalsevaluetrue0.1104649758352941massfalseixxtrue3.8057335631870236E-05ixytrue-6.9214884672569178E-08ixztrue-1.6145100576269089E-06iyytrue2.6291705432102431E-05iyztrue7.3462765424507441E-09izztrue1.5933633630625143E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue-0.004100.0668rpytrue00-1.5708originfalsefalselinktruearm_link5_linkparenttruelinktruearm_link6_linkchildtruexyztrue00-1axisfalselowertrue-3uppertrue3efforttrue3velocitytrue3limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 15:19:06,027 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 15:19:06,412 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_base_link to child arm_link1_link failed +2025-06-05 15:19:06,584 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 15:19:06,661 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 15:19:06,894 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 15:19:06,992 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 15:19:07,681 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 15:19:07,686 INFO ExportHelperExtension.cs: 1397 - Fixing components for arm_link3_link +2025-06-05 15:19:07,687 INFO ExportHelperExtension.cs: 1402 - Fixing 3030 +2025-06-05 15:19:07,688 INFO ExportHelperExtension.cs: 1402 - Fixing 3029 +2025-06-05 15:19:07,688 INFO ExportHelperExtension.cs: 1402 - Fixing 3035 +2025-06-05 15:19:07,688 INFO ExportHelperExtension.cs: 1402 - Fixing 3034 +2025-06-05 15:19:08,211 INFO : 0 - R1: 1, System.__ComObject, 1, System.Double[] +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 849 - L1: 0 +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 857 - L2: 0 +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 1352 - Unfixing component 3030 +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 1352 - Unfixing component 3029 +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 1352 - Unfixing component 3035 +2025-06-05 15:19:08,227 INFO ExportHelperExtension.cs: 1352 - Unfixing component 3034 +2025-06-05 15:19:08,697 ERROR ExportPropertyManager.cs: 399 - Exception caught handling button press 17 +System.Exception: Reference sketch does not exist + bei SW2URDF.URDFExport.ExportHelper.AddSketchGeometry(Origin Origin) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 696. + bei SW2URDF.URDFExport.ExportHelper.CreateRefOrigin(Origin Origin, String CoordinateSystemName) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 494. + bei SW2URDF.URDFExport.ExportHelper.CreateRefOrigin(Joint Joint) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 486. + bei SW2URDF.URDFExport.ExportHelper.CreateJoint(Link parent, Link child) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 454. + bei SW2URDF.URDFExport.ExportHelper.CreateLinkFromComponents(Link parent, LinkNode node) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 348. + bei SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 215. + bei SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 227. + bei SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 227. + bei SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 227. + bei SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 227. + bei SW2URDF.URDFExport.ExportHelper.CreateRobotFromTreeView(LinkNode baseNode) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:Zeile 169. + bei SW2URDF.URDFExport.ExportPropertyManager.ExportButtonPress() in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportPropertyManager.cs:Zeile 239. + bei SW2URDF.URDFExport.ExportPropertyManager.OnButtonPress(Int32 Id) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportPropertyManager.cs:Zeile 381. + bei SW2URDF.URDFExport.ExportPropertyManager.SolidWorks.Interop.swpublished.IPropertyManagerPage2Handler9.OnButtonPress(Int32 Id) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportPropertyManager.cs:Zeile 399. +2025-06-05 15:19:08,763 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:19:31,502 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 15:19:31,502 INFO SwAddin.cs: 299 - Save is required +2025-06-05 15:19:31,503 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 15:19:32,775 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 15:19:32,776 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 15:19:32,777 INFO ExportHelperExtension.cs: 1136 - Found 64 in URDF_Assembly.SLDASM +2025-06-05 15:19:32,778 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 15:19:32,779 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:19:32,779 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:19:32,779 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 15:19:32,780 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:19:32,780 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 15:19:32,781 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 15:19:32,781 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:19:32,782 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 15:19:32,782 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 15:19:32,783 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:19:32,783 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 15:19:32,784 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 15:19:32,787 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:19:32,787 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 15:19:32,788 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 15:19:32,789 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:19:32,789 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 15:19:32,790 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 15:19:32,790 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:19:32,791 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 15:19:32,791 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 15:19:32,792 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:19:32,792 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 15:19:32,793 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 15:19:32,793 INFO ExportHelperExtension.cs: 1136 - Found 64 in URDF_Assembly.SLDASM +2025-06-05 15:19:32,804 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 15:19:32,804 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:19:32,804 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:19:32,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:19:32,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 15:19:32,835 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 15:19:32,835 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:19:32,835 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 15:19:34,904 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 15:19:34,905 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration +2025-06-05 15:19:34,905 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 15:19:40,636 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:19:50,378 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:05,003 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:06,180 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:07,697 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:10,230 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:10,945 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:16,916 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:29,986 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:30,453 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:31,002 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:36,356 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:37,106 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:38,138 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:38,539 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:45,067 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:56,995 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:57,659 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:20:58,194 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:04,468 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:05,829 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:06,404 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:07,285 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:08,648 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:09,466 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:15,368 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:29,121 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:29,305 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:29,491 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:30,059 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:30,996 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:32,857 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:33,222 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:33,838 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:34,439 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:35,337 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:35,737 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:45,195 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:57,844 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:58,045 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:58,282 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:58,629 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:21:59,416 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:00,414 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:02,446 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:02,667 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:02,948 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:03,630 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:05,908 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:06,734 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:07,116 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:13,986 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 15:22:14,203 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 15:22:14,449 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child arm_link1_link failed +2025-06-05 15:22:14,676 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 15:22:14,735 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 15:22:14,974 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 15:22:15,035 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 15:22:15,736 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 15:22:15,803 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link3_link to child arm_link4_link failed +2025-06-05 15:22:16,371 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link5_link +2025-06-05 15:22:16,436 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link4_link to child arm_link5_link failed +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 15:22:17,352 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 15:22:17,384 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:22:17,385 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 15:22:17,386 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 15:22:17,386 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:22:17,387 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 15:22:17,387 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 15:22:17,388 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:22:17,388 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 15:22:17,389 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 15:22:17,389 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:22:17,389 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 15:22:17,390 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 15:22:17,390 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:22:17,391 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 15:22:17,391 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 15:22:17,391 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:22:17,392 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 15:22:17,392 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:22:17,393 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:22:17,393 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 15:22:17,393 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:22:17,394 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 15:22:17,394 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 15:22:17,394 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:22:17,395 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 15:22:17,395 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 15:22:17,396 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:22:17,396 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 15:22:17,396 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 15:22:17,397 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:22:17,397 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 15:22:17,397 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 15:22:17,398 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:22:17,398 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 15:22:17,398 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 15:22:17,399 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:22:17,399 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 15:22:17,400 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 15:22:17,400 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:22:17,400 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 15:22:17,520 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:22:20,196 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaarm_link3_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 15:22:41,527 INFO SwAddin.cs: 294 - Assembly export called for file URDF_Assembly.SLDASM +2025-06-05 15:22:41,527 INFO SwAddin.cs: 299 - Save is required +2025-06-05 15:22:41,527 INFO SwAddin.cs: 313 - Saving assembly +2025-06-05 15:22:42,793 INFO SwAddin.cs: 316 - Opening property manager +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 15:22:42,812 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:22:42,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 15:22:44,929 INFO SwAddin.cs: 339 - Loading config tree +2025-06-05 15:22:44,929 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue-0.0026322291536502763-0.000332098550481212120.047625035223114794rpytrue000originfalsefalsevaluetrue0.20022664001225823massfalseixxtrue0.0003051551862387095ixytrue5.9193755236109595E-09ixztrue-5.4825503909350469E-06iyytrue0.00018359540149694856iyztrue3.0317295193887823E-10izztrue0.00035672606786141161inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue4.4154208692082086E-090.000122631739122240620.035609609827141606rpytrue000originfalsefalsevaluetrue0.22723599679630302massfalseixxtrue0.00018080962544216389ixytrue1.9997215829397198E-12ixztrue3.6573543891079713E-13iyytrue0.00014143676473389556iyztrue-1.1207773361911784E-07izztrue0.00017414909124663803inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000.081300000000000136rpytrue001.5707963267948966originfalsefalselinktruebase_linkparenttruelinktruearm_link1_linkchildtruexyztrue00-1axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue-0.00485070416050022160.000134485688723283430.1511532654753473rpytrue000originfalsefalsevaluetrue0.30840727396891277massfalseixxtrue0.00053626238823764041ixytrue-5.5942074316664914E-07ixztrue4.559694194742112E-05iyytrue0.00046361979440484553iyztrue-5.41211328309889E-05izztrue0.00028846236115287845inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue00.00200000000000436630.092999999999999958rpytrue01.2215393204017337-1.570796326794897originfalsefalselinktruearm_link1_linkparenttruelinktruearm_link2_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue-2.3472862743928458E-050.00022272416164961090.12165732110722122rpytrue000originfalsefalsevaluetrue0.21522368186867635massfalseixxtrue0.00018788748127738012ixytrue1.2953244973073631E-09ixztrue-2.4839754756668889E-09iyytrue0.00017700579523914257iyztrue-1.9538129798688983E-05izztrue5.9636218780074904E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaarm_link3_jointtypetruerevolutexyztrue-0.05000000000000001700.29000000000000015rpytrue-3.1415926535897931-0.31921087302860063-3.1415926535897931originfalsefalselinktruearm_link2_linkparenttruelinktruearm_link3_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue-6.4509028821768677E-05-2.7807706924502795E-050.042141040827551338rpytrue000originfalsefalsevaluetrue0.079997620319299911massfalseixxtrue2.9827516727776809E-05ixytrue-3.7887086535963645E-10ixztrue2.4264393814119046E-10iyytrue1.6057754086664228E-05iyztrue1.0683105812522641E-09izztrue2.0042121601260574E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue00.000600000000000953940.26473074193981477rpytrue00.0300461333645552640originfalsefalselinktruearm_link3_linkparenttruelinktruearm_link4_linkchildtruexyztrue0-10axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue0.0038215060578492555-7.8562176892595093E-050.034001750714024781rpytrue000originfalsefalsevaluetrue0.0824183861074839massfalseixxtrue1.3465197030142119E-05ixytrue1.0651017655427296E-09ixztrue7.3315158306387834E-09iyytrue3.0652368560949627E-05iyztrue3.77177397828811E-10izztrue3.0909130383325344E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue-0.000550000000009293069.9999999999933475E-050.074330741939814968rpytrue000originfalsefalselinktruearm_link4_linkparenttruelinktruearm_link5_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 15:22:44,929 INFO LinkNode.cs: 35 - Building node base_link +2025-06-05 15:22:44,929 INFO LinkNode.cs: 35 - Building node arm_link1_link +2025-06-05 15:22:44,929 INFO LinkNode.cs: 35 - Building node arm_link2_link +2025-06-05 15:22:44,929 INFO LinkNode.cs: 35 - Building node arm_link3_link +2025-06-05 15:22:44,929 INFO LinkNode.cs: 35 - Building node arm_link4_link +2025-06-05 15:22:44,929 INFO LinkNode.cs: 35 - Building node arm_link5_link +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_basis-1@URDF_Assembly? +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\01_Baugrupppe_Drehkranz\URDF_basis.SLDPRT +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link1_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_schulter-1@URDF_Assembly? +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\01_Baugrupppe_Drehkranz\URDF_schulter.SLDPRT +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link1_link +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link2_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:22:44,929 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_oberarm-1@URDF_Assembly? +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\02_Baugruppe_Glied_1\URDF_oberarm.SLDPRT +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link2_link +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link3_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_unterarm-1@URDF_Assembly? +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\03_Baugruppe_Glied_2\URDF_unterarm.SLDPRT +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link3_link +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link4_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_hand_kipp-1@URDF_Assembly? +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\04_Baugruppe_Glied_3\URDF_hand_kipp.SLDPRT +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link4_link +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for arm_link5_link from C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\URDF_Assembly.SLDASM +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 245 - Loading component with PID hB???URDF_hand_dreh-1@URDF_Assembly? +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\offic\Desktop\Projekt_Res.QBot_Arm\01_CAD_Konstruktion\05_Baugruppe_Drehung\URDF_hand_dreh.SLDPRT +2025-06-05 15:22:44,945 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link arm_link5_link +2025-06-05 15:22:45,028 INFO SwAddin.cs: 344 - Showing property manager +2025-06-05 15:22:51,244 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:06,117 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:06,604 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:06,919 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:07,315 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:07,720 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:08,636 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:09,090 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:10,504 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:11,152 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:11,436 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:11,690 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:11,919 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:12,351 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:13,167 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:13,507 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:33,563 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:23:52,718 INFO ExportPropertyManager.cs: 422 - Configuration saved +2025-06-05 15:23:52,718 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue-0.0026322291536502763-0.000332098550481212120.047625035223114794rpytrue000originfalsefalsevaluetrue0.20022664001225823massfalseixxtrue0.0003051551862387095ixytrue5.9193755236109595E-09ixztrue-5.4825503909350469E-06iyytrue0.00018359540149694856iyztrue3.0317295193887823E-10izztrue0.00035672606786141161inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue4.4154208692082086E-090.000122631739122240620.035609609827141606rpytrue000originfalsefalsevaluetrue0.22723599679630302massfalseixxtrue0.00018080962544216389ixytrue1.9997215829397198E-12ixztrue3.6573543891079713E-13iyytrue0.00014143676473389556iyztrue-1.1207773361911784E-07izztrue0.00017414909124663803inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000.081300000000000136rpytrue001.5707963267948966originfalsefalselinktruebase_linkparenttruelinktruearm_link1_linkchildtruexyztrue00-1axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue-0.00485070416050022160.000134485688723283430.1511532654753473rpytrue000originfalsefalsevaluetrue0.30840727396891277massfalseixxtrue0.00053626238823764041ixytrue-5.5942074316664914E-07ixztrue4.559694194742112E-05iyytrue0.00046361979440484553iyztrue-5.41211328309889E-05izztrue0.00028846236115287845inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue00.00200000000000436630.092999999999999958rpytrue01.2215393204017337-1.570796326794897originfalsefalselinktruearm_link1_linkparenttruelinktruearm_link2_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue-2.3472862743928458E-050.00022272416164961090.12165732110722122rpytrue000originfalsefalsevaluetrue0.21522368186867635massfalseixxtrue0.00018788748127738012ixytrue1.2953244973073631E-09ixztrue-2.4839754756668889E-09iyytrue0.00017700579523914257iyztrue-1.9538129798688983E-05izztrue5.9636218780074904E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaarm_link3_jointtypetruerevolutexyztrue-0.05000000000000001700.29000000000000015rpytrue-3.1415926535897931-0.31921087302860063-3.1415926535897931originfalsefalselinktruearm_link2_linkparenttruelinktruearm_link3_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue-6.4509028821768677E-05-2.7807706924502795E-050.042141040827551338rpytrue000originfalsefalsevaluetrue0.079997620319299911massfalseixxtrue2.9827516727776809E-05ixytrue-3.7887086535963645E-10ixztrue2.4264393814119046E-10iyytrue1.6057754086664228E-05iyztrue1.0683105812522641E-09izztrue2.0042121601260574E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue00.000600000000000953940.26473074193981477rpytrue00.0300461333645552640originfalsefalselinktruearm_link3_linkparenttruelinktruearm_link4_linkchildtruexyztrue0-10axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue0.0038215060578492555-7.8562176892595093E-050.034001750714024781rpytrue000originfalsefalsevaluetrue0.0824183861074839massfalseixxtrue1.3465197030142119E-05ixytrue1.0651017655427296E-09ixztrue7.3315158306387834E-09iyytrue3.0652368560949627E-05iyztrue3.77177397828811E-10izztrue3.0909130383325344E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue-0.000550000000009293069.9999999999933475E-050.074330741939814968rpytrue000originfalsefalselinktruearm_link4_linkparenttruelinktruearm_link5_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 15:23:52,900 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link1_link +2025-06-05 15:23:52,986 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child arm_link1_link failed +2025-06-05 15:23:53,148 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link2_link +2025-06-05 15:23:53,216 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link1_link to child arm_link2_link failed +2025-06-05 15:23:53,448 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link3_link +2025-06-05 15:23:53,532 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link2_link to child arm_link3_link failed +2025-06-05 15:23:54,233 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link4_link +2025-06-05 15:23:54,300 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link3_link to child arm_link4_link failed +2025-06-05 15:23:54,876 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link5_link +2025-06-05 15:23:54,950 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link4_link to child arm_link5_link failed +2025-06-05 15:23:55,505 INFO ExportHelperExtension.cs: 347 - Creating joint arm_link6_link +2025-06-05 15:23:55,584 WARN ExportHelperExtension.cs: 351 - Creating joint from parent arm_link5_link to child arm_link6_link failed +2025-06-05 15:23:57,501 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Assembly.SLDASM +2025-06-05 15:23:57,502 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:23:57,502 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in URDF_Assembly.SLDASM +2025-06-05 15:23:57,502 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:23:57,502 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:23:57,502 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_dreh-1 +2025-06-05 15:23:57,518 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:23:57,518 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_dreh-1 +2025-06-05 15:23:57,518 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_unterarm-1 +2025-06-05 15:23:57,518 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_unterarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_basis-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_basis-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_hand_kipp-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_hand_kipp-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_oberarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_oberarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_schulter-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_schulter-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from URDF_Greifer-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in URDF_Greifer-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Assembly.SLDASM +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 65 in URDF_Assembly.SLDASM +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in URDF_Assembly.SLDASM +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_dreh-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_hand_dreh-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_dreh-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_unterarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 38 in URDF_unterarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_unterarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_basis-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 41 in URDF_basis-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [RefAxis] in URDF_basis-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_hand_kipp-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 34 in URDF_hand_kipp-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_hand_kipp-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_oberarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 30 in URDF_oberarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_oberarm-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_schulter-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 33 in URDF_schulter-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_schulter-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from URDF_Greifer-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1136 - Found 43 in URDF_Greifer-1 +2025-06-05 15:23:57,533 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in URDF_Greifer-1 +2025-06-05 15:23:57,676 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2025-06-05 15:34:20,094 INFO AssemblyExportForm.cs: 253 - Completing URDF export +2025-06-05 15:34:20,094 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue-0.0026322291536502763-0.000332098550481212120.047625035223114794rpytrue000originfalsefalsevaluetrue0.20022664001225823massfalseixxtrue0.0003051551862387095ixytrue5.9193755236109595E-09ixztrue-5.4825503909350469E-06iyytrue0.00018359540149694856iyztrue3.0317295193887823E-10izztrue0.00035672606786141161inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebase_systemlinktruenametruearm_link1_linkxyztrue4.4154208692082086E-090.000122631739122240620.035609609827141606rpytrue000originfalsefalsevaluetrue0.22723599679630302massfalseixxtrue0.00018080962544216389ixytrue1.9997215829397198E-12ixztrue3.6573543891079713E-13iyytrue0.00014143676473389556iyztrue-1.1207773361911784E-07izztrue0.00017414909124663803inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link1_jointtypetruerevolutexyztrue000.081300000000000136rpytrue001.5707963267948966originfalsefalselinktruebase_linkparenttruelinktruearm_link1_linkchildtruexyztrue00-1axisfalselowertrueuppertrueefforttruevelocitytruelimittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse8shoulder_systemlinktruenametruearm_link2_linkxyztrue-0.00485070416050022160.000134485688723283430.1511532654753473rpytrue000originfalsefalsevaluetrue0.30840727396891277massfalseixxtrue0.00053626238823764041ixytrue-5.5942074316664914E-07ixztrue4.559694194742112E-05iyytrue0.00046361979440484553iyztrue-5.41211328309889E-05izztrue0.00028846236115287845inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link2_jointtypetruerevolutexyztrue00.00200000000000436630.092999999999999958rpytrue01.2215393204017337-1.570796326794897originfalsefalselinktruearm_link1_linkparenttruelinktruearm_link2_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse9upper_arm_systemlinktruenametruearm_link3_linkxyztrue-2.3472862743928458E-050.00022272416164961090.12165732110722122rpytrue000originfalsefalsevaluetrue0.21522368186867635massfalseixxtrue0.00018788748127738012ixytrue1.2953244973073631E-09ixztrue-2.4839754756668889E-09iyytrue0.00017700579523914257iyztrue-1.9538129798688983E-05izztrue5.9636218780074904E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaarm_link3_jointtypetruerevolutexyztrue-0.05000000000000001700.29000000000000015rpytrue-3.1415926535897931-0.31921087302860063-3.1415926535897931originfalsefalselinktruearm_link2_linkparenttruelinktruearm_link3_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse10forearm_systemlinktruenametruearm_link4_linkxyztrue-6.4509028821768677E-05-2.7807706924502795E-050.042141040827551338rpytrue000originfalsefalsevaluetrue0.079997620319299911massfalseixxtrue2.9827516727776809E-05ixytrue-3.7887086535963645E-10ixztrue2.4264393814119046E-10iyytrue1.6057754086664228E-05iyztrue1.0683105812522641E-09izztrue2.0042121601260574E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link4_jointtypetruerevolutexyztrue00.000600000000000953940.26473074193981477rpytrue00.0300461333645552640originfalsefalselinktruearm_link3_linkparenttruelinktruearm_link4_linkchildtruexyztrue0-10axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse11hand_pitch_systemlinktruenametruearm_link5_linkxyztrue0.0038215060578492555-7.8562176892595093E-050.034001750714024781rpytrue000originfalsefalsevaluetrue0.0824183861074839massfalseixxtrue1.3465197030142119E-05ixytrue1.0651017655427296E-09ixztrue7.3315158306387834E-09iyytrue3.0652368560949627E-05iyztrue3.77177397828811E-10izztrue3.0909130383325344E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link5_jointtypetruerevolutexyztrue-0.000550000000009293069.9999999999933475E-050.074330741939814968rpytrue000originfalsefalselinktruearm_link4_linkparenttruelinktruearm_link5_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse12hand_yaw_systemlinktruenametruearm_link6_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruearm_link6_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAchse13hand_spin_systemlinktruefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAEcAcgBlAGkAZgBlAHIALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA2QsAAA==falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBkAHIAZQBoAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANgLAAA=falsefalsefalseaEIAAAUAAAD//v8eVQBSAEQARgBfAGgAYQBuAGQAXwBrAGkAcABwAC0AMQBAAFUAUgBEAEYAXwBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAANcLAAA=falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHUAbgB0AGUAcgBhAHIAbQAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADWCwAAfalsefalsefalseaEIAAAUAAAD//v8cVQBSAEQARgBfAG8AYgBlAHIAYQByAG0ALQAxAEAAVQBSAEQARgBfAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAA1QsAAA==falsefalsefalseaEIAAAUAAAD//v8dVQBSAEQARgBfAHMAYwBoAHUAbAB0AGUAcgAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADbCwAAfalsefalsefalseaEIAAAUAAAD//v8aVQBSAEQARgBfAGIAYQBzAGkAcwAtADEAQABVAFIARABGAF8AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAADaCwAAfalsefalse +2025-06-05 15:35:01,539 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\offic\Desktop\URDF_arm_URDF2 +2025-06-05 15:35:01,539 INFO ExportHelper.cs: 147 - Beginning the export process +2025-06-05 15:35:01,539 INFO ExportHelper.cs: 153 - Creating package directories with name URDF_arm_URDF2 and save path C:\Users\offic\Desktop +2025-06-05 15:35:04,888 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at C:\Users\offic\Desktop\URDF_arm_URDF2\CMakeLists.txt +2025-06-05 15:35:04,890 INFO ExportHelper.cs: 166 - Creating joint names config at C:\Users\offic\Desktop\URDF_arm_URDF2\config\joint_names_URDF_arm_URDF2.yaml +2025-06-05 15:35:04,890 INFO ExportHelper.cs: 170 - Creating package.xml at C:\Users\offic\Desktop\URDF_arm_URDF2\package.xml +2025-06-05 15:35:04,890 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\offic\Desktop\URDF_arm_URDF2\package.xml +2025-06-05 15:35:04,890 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in C:\Users\offic\Desktop\URDF_arm_URDF2\launch\ +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in C:\Users\offic\Desktop\URDF_arm_URDF2\launch\ +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 187 - Saving existing STL preferences +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 450 - Saving users preferences +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 190 - Modifying STL preferences +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 464 - Setting STL preferences +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 196 - Found 0 hidden components +2025-06-05 15:35:04,906 INFO ExportHelper.cs: 197 - Hiding all components +2025-06-05 15:35:05,290 INFO ExportHelper.cs: 204 - Beginning individual files export +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: base_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link base_link has 1 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: arm_link1_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link arm_link1_link has 1 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: arm_link2_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link arm_link2_link has 1 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: arm_link3_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link arm_link3_link has 1 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: arm_link4_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link arm_link4_link has 1 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: arm_link5_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link arm_link5_link has 1 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 270 - Exporting link: arm_link6_link +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 272 - Link arm_link6_link has 0 children +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 317 - arm_link6_link: Exporting STL with coordinate frame hand_spin_system +2025-06-05 15:35:05,292 INFO ExportHelper.cs: 322 - arm_link6_link: Reference geometry name +2025-06-05 15:35:06,075 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\arm_link6_link.STL +2025-06-05 15:35:08,060 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:08,061 INFO ExportHelper.cs: 317 - arm_link5_link: Exporting STL with coordinate frame hand_yaw_system +2025-06-05 15:35:08,062 INFO ExportHelper.cs: 322 - arm_link5_link: Reference geometry name +2025-06-05 15:35:08,111 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\arm_link5_link.STL +2025-06-05 15:35:08,724 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:08,724 INFO ExportHelper.cs: 317 - arm_link4_link: Exporting STL with coordinate frame hand_pitch_system +2025-06-05 15:35:08,724 INFO ExportHelper.cs: 322 - arm_link4_link: Reference geometry name +2025-06-05 15:35:08,792 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\arm_link4_link.STL +2025-06-05 15:35:09,455 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:09,455 INFO ExportHelper.cs: 317 - arm_link3_link: Exporting STL with coordinate frame forearm_system +2025-06-05 15:35:09,455 INFO ExportHelper.cs: 322 - arm_link3_link: Reference geometry name +2025-06-05 15:35:09,781 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\arm_link3_link.STL +2025-06-05 15:35:10,663 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:10,664 INFO ExportHelper.cs: 317 - arm_link2_link: Exporting STL with coordinate frame upper_arm_system +2025-06-05 15:35:10,665 INFO ExportHelper.cs: 322 - arm_link2_link: Reference geometry name +2025-06-05 15:35:10,873 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\arm_link2_link.STL +2025-06-05 15:35:11,192 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:11,192 INFO ExportHelper.cs: 317 - arm_link1_link: Exporting STL with coordinate frame shoulder_system +2025-06-05 15:35:11,208 INFO ExportHelper.cs: 322 - arm_link1_link: Reference geometry name +2025-06-05 15:35:11,271 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\arm_link1_link.STL +2025-06-05 15:35:11,569 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:11,570 INFO ExportHelper.cs: 317 - base_link: Exporting STL with coordinate frame base_system +2025-06-05 15:35:11,570 INFO ExportHelper.cs: 322 - base_link: Reference geometry name +2025-06-05 15:35:11,624 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\offic\Desktop\URDF_arm_URDF2\meshes\base_link.STL +2025-06-05 15:35:11,772 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2025-06-05 15:35:11,773 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components +2025-06-05 15:35:12,575 INFO ExportHelper.cs: 145 - Resetting STL preferences +2025-06-05 15:35:12,576 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2025-06-05 15:35:12,576 INFO ExportHelper.cs: 228 - Writing URDF file to C:\Users\offic\Desktop\URDF_arm_URDF2\urdf\URDF_arm_URDF2.urdf +2025-06-05 15:35:12,993 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\offic\Desktop\URDF_arm_URDF2\urdf\URDF_arm_URDF2.csv +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2025-06-05 15:35:13,025 INFO ExportHelper.cs: 234 - Copying log file +2025-06-05 15:35:13,025 INFO ExportHelper.cs: 439 - Copying C:\Users\offic\sw2urdf_logs\sw2urdf.log to C:\Users\offic\Desktop\URDF_arm_URDF2\export.log diff --git a/old stuff/URDF_arm_URDF2/launch/display.launch b/old stuff/URDF_arm_URDF2/launch/display.launch new file mode 100644 index 0000000..27ad59e --- /dev/null +++ b/old stuff/URDF_arm_URDF2/launch/display.launch @@ -0,0 +1,20 @@ + + + + + + + \ No newline at end of file diff --git a/old stuff/URDF_arm_URDF2/launch/gazebo.launch b/old stuff/URDF_arm_URDF2/launch/gazebo.launch new file mode 100644 index 0000000..08a691f --- /dev/null +++ b/old stuff/URDF_arm_URDF2/launch/gazebo.launch @@ -0,0 +1,20 @@ + + + + + + \ No newline at end of file diff --git a/old stuff/URDF_arm_URDF2/meshes/arm_link1_link.STL b/old stuff/URDF_arm_URDF2/meshes/arm_link1_link.STL new file mode 100644 index 0000000..ea176bf Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/arm_link1_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/meshes/arm_link2_link.STL b/old stuff/URDF_arm_URDF2/meshes/arm_link2_link.STL new file mode 100644 index 0000000..17c6415 Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/arm_link2_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/meshes/arm_link3_link.STL b/old stuff/URDF_arm_URDF2/meshes/arm_link3_link.STL new file mode 100644 index 0000000..2f869c5 Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/arm_link3_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/meshes/arm_link4_link.STL b/old stuff/URDF_arm_URDF2/meshes/arm_link4_link.STL new file mode 100644 index 0000000..3ff5fa7 Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/arm_link4_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/meshes/arm_link5_link.STL b/old stuff/URDF_arm_URDF2/meshes/arm_link5_link.STL new file mode 100644 index 0000000..6dc314d Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/arm_link5_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/meshes/arm_link6_link.STL b/old stuff/URDF_arm_URDF2/meshes/arm_link6_link.STL new file mode 100644 index 0000000..1164072 Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/arm_link6_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/meshes/base_link.STL b/old stuff/URDF_arm_URDF2/meshes/base_link.STL new file mode 100644 index 0000000..12e6cc0 Binary files /dev/null and b/old stuff/URDF_arm_URDF2/meshes/base_link.STL differ diff --git a/old stuff/URDF_arm_URDF2/package.xml b/old stuff/URDF_arm_URDF2/package.xml new file mode 100644 index 0000000..e30b60b --- /dev/null +++ b/old stuff/URDF_arm_URDF2/package.xml @@ -0,0 +1,21 @@ + + URDF_arm_URDF2 + 1.0.0 + +

URDF Description package for URDF_arm_URDF2

+

This package contains configuration data, 3D models and launch files +for URDF_arm_URDF2 robot

+
+ TODO + + BSD + catkin + roslaunch + robot_state_publisher + rviz + joint_state_publisher_gui + gazebo + + + +
\ No newline at end of file diff --git a/old stuff/URDF_arm_URDF2/urdf/URDF_arm_URDF2.csv b/old stuff/URDF_arm_URDF2/urdf/URDF_arm_URDF2.csv new file mode 100644 index 0000000..0a4ad7a --- /dev/null +++ b/old stuff/URDF_arm_URDF2/urdf/URDF_arm_URDF2.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,"-0,0026322","-0,0003321","0,047625",0,0,0,"0,20023","0,00030516","5,9194E-09","-5,4826E-06","0,0001836","3,0317E-10","0,00035673",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/base_link.STL,"0,79216","0,81961","0,93333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/base_link.STL,,URDF_basis-1,base_system,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +arm_link1_link,"4,4154E-09","0,00012263","0,03561",0,0,0,"0,22724","0,00018081","1,9997E-12","3,6574E-13","0,00014144","-1,1208E-07","0,00017415",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link1_link.STL,"0,79216","0,81961","0,93333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link1_link.STL,,URDF_schulter-1,shoulder_system,Achse8,arm_link1_joint,revolute,0,0,"0,0813",0,0,"1,5708",base_link,0,0,-1,3,2,-3,3,,,,,,,, +arm_link2_link,"-0,00485070416050022","0,000134485688723283","0,151153265475347",0,0,0,"0,308407273968913","0,00053626238823764","-5,59420743166653E-07","4,55969419474211E-05","0,000463619794404845","-5,41211328309889E-05","0,000288462361152878",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link2_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link2_link.STL,,URDF_oberarm-1,upper_arm_system,Achse9,arm_link2_joint,revolute,0,"0,002","0,093",0,"1,2215","-1,5708",arm_link1_link,0,1,0,3,2,"0,3","-2,6",,,,,,,, +arm_link3_link,"-2,34728627439007E-05","0,000222724161649632","0,121657321107221",0,0,0,"0,215223681868676","0,00018788748127738","1,29532449730699E-09","-2,48397547566625E-09","0,000177005795239143","-1,9538129798689E-05","5,96362187800749E-05",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link3_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link3_link.STL,,URDF_unterarm-1,forearm_system,Achse10,arm_link3_joint,revolute,"-0,05",0,"0,29","-3,1416","-0,31921","-3,1416",arm_link2_link,0,1,0,3,2,"-0,5",3,,,,,,,, +arm_link4_link,"-6,45090288216854E-05","-2,78077069245028E-05","0,0421410408275514",0,0,0,"0,0799976203192999","2,98275167277768E-05","-3,78870865359705E-10","2,42643938141168E-10","1,60577540866642E-05","1,06831058125207E-09","2,00421216012606E-05",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link4_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link4_link.STL,,URDF_hand_kipp-1,hand_pitch_system,Achse11,arm_link4_joint,revolute,0,"0,0006","0,26473",0,"0,030046",0,arm_link3_link,0,-1,0,3,2,"-1,5","1,5",,,,,,,, +arm_link5_link,"0,00382150605784931","-7,8562176892609E-05","0,0340017507140248",0,0,0,"0,0824183861074839","1,34651970301421E-05","1,06510176554276E-09","7,33151583063895E-09","3,06523685609496E-05","3,77177397828779E-10","3,09091303833253E-05",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link5_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link5_link.STL,,URDF_hand_dreh-1,hand_yaw_system,Achse12,arm_link5_joint,revolute,"-0,00055","0,0001","0,074331",0,0,0,arm_link4_link,1,0,0,3,2,"-1,5","1,5",,,,,,,, +arm_link6_link,"0,0143574958730017","0,00228204903930826","0,0446512981778694",0,0,0,"0,110464975834032","3,80573356318669E-05","-6,92148846737554E-08","-1,61451005762754E-06","2,62917054320992E-05","7,34627654365672E-09","1,59336336306222E-05",0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link6_link.STL,"0,792156862745098","0,819607843137255","0,933333333333333",1,0,0,0,0,0,0,package://URDF_arm_URDF2/meshes/arm_link6_link.STL,,URDF_Greifer-1,hand_spin_system,Achse13,arm_link6_joint,revolute,"0,022033",0,"0,0668",0,0,0,arm_link5_link,0,0,1,3,2,-3,3,,,,,,,, diff --git a/old stuff/URDF_arm_URDF2/urdf/URDF_arm_URDF2.urdf b/old stuff/URDF_arm_URDF2/urdf/URDF_arm_URDF2.urdf new file mode 100644 index 0000000..8225899 --- /dev/null +++ b/old stuff/URDF_arm_URDF2/urdf/URDF_arm_URDF2.urdf @@ -0,0 +1,395 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/resqbot_drive_interface/99-arduino-udev.rules b/old stuff/resqbot_drive_interface/99-arduino-udev.rules similarity index 100% rename from resqbot_drive_interface/99-arduino-udev.rules rename to old stuff/resqbot_drive_interface/99-arduino-udev.rules diff --git a/resqbot_drive_interface/LICENSE b/old stuff/resqbot_drive_interface/LICENSE similarity index 100% rename from resqbot_drive_interface/LICENSE rename to old stuff/resqbot_drive_interface/LICENSE diff --git a/resqbot_drive_interface/README.md b/old stuff/resqbot_drive_interface/README.md similarity index 100% rename from resqbot_drive_interface/README.md rename to old stuff/resqbot_drive_interface/README.md diff --git a/resqbot_drive_interface/launch/default_launch.py b/old stuff/resqbot_drive_interface/launch/default_launch.py similarity index 100% rename from resqbot_drive_interface/launch/default_launch.py rename to old stuff/resqbot_drive_interface/launch/default_launch.py diff --git a/resqbot_drive_interface/package.xml b/old stuff/resqbot_drive_interface/package.xml similarity index 100% rename from resqbot_drive_interface/package.xml rename to old stuff/resqbot_drive_interface/package.xml diff --git a/resqbot_drive_interface/resource/resqbot_drive_interface b/old stuff/resqbot_drive_interface/resource/resqbot_drive_interface similarity index 100% rename from resqbot_drive_interface/resource/resqbot_drive_interface rename to old stuff/resqbot_drive_interface/resource/resqbot_drive_interface diff --git a/resqbot_drive_interface/resqbot_drive_interface/__init__.py b/old stuff/resqbot_drive_interface/resqbot_drive_interface/__init__.py similarity index 100% rename from resqbot_drive_interface/resqbot_drive_interface/__init__.py rename to old stuff/resqbot_drive_interface/resqbot_drive_interface/__init__.py diff --git a/resqbot_drive_interface/resqbot_drive_interface/__pycache__/__init__.cpython-310.pyc b/old stuff/resqbot_drive_interface/resqbot_drive_interface/__pycache__/__init__.cpython-310.pyc similarity index 100% rename from resqbot_drive_interface/resqbot_drive_interface/__pycache__/__init__.cpython-310.pyc rename to old stuff/resqbot_drive_interface/resqbot_drive_interface/__pycache__/__init__.cpython-310.pyc diff --git a/resqbot_drive_interface/resqbot_drive_interface/__pycache__/drive_interface.cpython-310.pyc b/old stuff/resqbot_drive_interface/resqbot_drive_interface/__pycache__/drive_interface.cpython-310.pyc similarity index 100% rename from resqbot_drive_interface/resqbot_drive_interface/__pycache__/drive_interface.cpython-310.pyc rename to old stuff/resqbot_drive_interface/resqbot_drive_interface/__pycache__/drive_interface.cpython-310.pyc diff --git a/resqbot_drive_interface/resqbot_drive_interface/drive_interface.py b/old stuff/resqbot_drive_interface/resqbot_drive_interface/drive_interface.py similarity index 100% rename from resqbot_drive_interface/resqbot_drive_interface/drive_interface.py rename to old stuff/resqbot_drive_interface/resqbot_drive_interface/drive_interface.py diff --git a/resqbot_drive_interface/setup.cfg b/old stuff/resqbot_drive_interface/setup.cfg similarity index 100% rename from resqbot_drive_interface/setup.cfg rename to old stuff/resqbot_drive_interface/setup.cfg diff --git a/resqbot_drive_interface/setup.py b/old stuff/resqbot_drive_interface/setup.py similarity index 100% rename from resqbot_drive_interface/setup.py rename to old stuff/resqbot_drive_interface/setup.py diff --git a/resqbot_drive_interface/test/test_copyright.py b/old stuff/resqbot_drive_interface/test/test_copyright.py similarity index 100% rename from resqbot_drive_interface/test/test_copyright.py rename to old stuff/resqbot_drive_interface/test/test_copyright.py diff --git a/resqbot_drive_interface/test/test_flake8.py b/old stuff/resqbot_drive_interface/test/test_flake8.py similarity index 100% rename from resqbot_drive_interface/test/test_flake8.py rename to old stuff/resqbot_drive_interface/test/test_flake8.py diff --git a/resqbot_drive_interface/test/test_pep257.py b/old stuff/resqbot_drive_interface/test/test_pep257.py similarity index 100% rename from resqbot_drive_interface/test/test_pep257.py rename to old stuff/resqbot_drive_interface/test/test_pep257.py diff --git a/resqbot_flipper_interface/99-arduino-udev.rules b/old stuff/resqbot_flipper_interface/99-arduino-udev.rules similarity index 100% rename from resqbot_flipper_interface/99-arduino-udev.rules rename to old stuff/resqbot_flipper_interface/99-arduino-udev.rules diff --git a/resqbot_flipper_interface/LICENSE b/old stuff/resqbot_flipper_interface/LICENSE similarity index 100% rename from resqbot_flipper_interface/LICENSE rename to old stuff/resqbot_flipper_interface/LICENSE diff --git a/resqbot_flipper_interface/README.md b/old stuff/resqbot_flipper_interface/README.md similarity index 100% rename from resqbot_flipper_interface/README.md rename to old stuff/resqbot_flipper_interface/README.md diff --git a/resqbot_flipper_interface/launch/default_launch.py b/old stuff/resqbot_flipper_interface/launch/default_launch.py similarity index 100% rename from resqbot_flipper_interface/launch/default_launch.py rename to old stuff/resqbot_flipper_interface/launch/default_launch.py diff --git a/resqbot_flipper_interface/package.xml b/old stuff/resqbot_flipper_interface/package.xml similarity index 100% rename from resqbot_flipper_interface/package.xml rename to old stuff/resqbot_flipper_interface/package.xml diff --git a/resqbot_flipper_interface/resource/resqbot_flipper_interface b/old stuff/resqbot_flipper_interface/resource/resqbot_flipper_interface similarity index 100% rename from resqbot_flipper_interface/resource/resqbot_flipper_interface rename to old stuff/resqbot_flipper_interface/resource/resqbot_flipper_interface diff --git a/resqbot_flipper_interface/resqbot_flipper_interface/__init__.py b/old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__init__.py similarity index 100% rename from resqbot_flipper_interface/resqbot_flipper_interface/__init__.py rename to old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__init__.py diff --git a/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/__init__.cpython-310.pyc b/old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/__init__.cpython-310.pyc similarity index 100% rename from resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/__init__.cpython-310.pyc rename to old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/__init__.cpython-310.pyc diff --git a/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/drive_interface.cpython-310.pyc b/old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/drive_interface.cpython-310.pyc similarity index 100% rename from resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/drive_interface.cpython-310.pyc rename to old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/drive_interface.cpython-310.pyc diff --git a/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/flipper_interface.cpython-310.pyc b/old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/flipper_interface.cpython-310.pyc similarity index 100% rename from resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/flipper_interface.cpython-310.pyc rename to old stuff/resqbot_flipper_interface/resqbot_flipper_interface/__pycache__/flipper_interface.cpython-310.pyc diff --git a/resqbot_flipper_interface/resqbot_flipper_interface/flipper_interface.py b/old stuff/resqbot_flipper_interface/resqbot_flipper_interface/flipper_interface.py similarity index 100% rename from resqbot_flipper_interface/resqbot_flipper_interface/flipper_interface.py rename to old stuff/resqbot_flipper_interface/resqbot_flipper_interface/flipper_interface.py diff --git a/resqbot_flipper_interface/setup.cfg b/old stuff/resqbot_flipper_interface/setup.cfg similarity index 100% rename from resqbot_flipper_interface/setup.cfg rename to old stuff/resqbot_flipper_interface/setup.cfg diff --git a/resqbot_flipper_interface/setup.py b/old stuff/resqbot_flipper_interface/setup.py similarity index 100% rename from resqbot_flipper_interface/setup.py rename to old stuff/resqbot_flipper_interface/setup.py diff --git a/resqbot_flipper_interface/test/test_copyright.py b/old stuff/resqbot_flipper_interface/test/test_copyright.py similarity index 100% rename from resqbot_flipper_interface/test/test_copyright.py rename to old stuff/resqbot_flipper_interface/test/test_copyright.py diff --git a/resqbot_flipper_interface/test/test_flake8.py b/old stuff/resqbot_flipper_interface/test/test_flake8.py similarity index 100% rename from resqbot_flipper_interface/test/test_flake8.py rename to old stuff/resqbot_flipper_interface/test/test_flake8.py diff --git a/resqbot_flipper_interface/test/test_pep257.py b/old stuff/resqbot_flipper_interface/test/test_pep257.py similarity index 100% rename from resqbot_flipper_interface/test/test_pep257.py rename to old stuff/resqbot_flipper_interface/test/test_pep257.py diff --git a/save_map.sh b/save_map.sh new file mode 100755 index 0000000..ab9f7c2 --- /dev/null +++ b/save_map.sh @@ -0,0 +1,5 @@ +#!/bin/bash +source /opt/ros/humble/setup.bash && +source /etc/ros/env.sh && +ros2 service call /map_save std_srvs/srv/Trigger {} && +scp resqbots@192.168.0.43:/home/resqbots/maps/last_map.pcd /home/paul/maps/last_raspi_map.pcd diff --git a/view_map.sh b/view_map.sh new file mode 100755 index 0000000..da880f6 --- /dev/null +++ b/view_map.sh @@ -0,0 +1,2 @@ +#!/bin/bash +pcl_viewer /home/paul/maps/last_raspi_map.pcd diff --git a/web_video_server/AUTHORS.md b/web_video_server/AUTHORS.md deleted file mode 100644 index cf18e30..0000000 --- a/web_video_server/AUTHORS.md +++ /dev/null @@ -1,9 +0,0 @@ -Original Authors ----------------- - - * Mitchell Wills (mwills@wpi.edu) - -Contributors ------------- - - * [Russell Toris](http://users.wpi.edu/~rctoris/) (rctoris@wpi.edu) diff --git a/web_video_server/CHANGELOG.rst b/web_video_server/CHANGELOG.rst deleted file mode 100644 index 785d3a9..0000000 --- a/web_video_server/CHANGELOG.rst +++ /dev/null @@ -1,145 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package web_video_server -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.0.0 (2019-09-20) ------------------- -* Port to ROS 2 - -0.2.1 (2019-06-05) ------------------- -* Restream buffered frames with minimum publish rate (`#88 `_) - * Restream buffered frames with minimum publish rate - * Implement restreaming for ros_compressed_streamer -* Update travis config (`#89 `_) -* Fall back to mjpeg if ros_compressed is unavailable (`#87 `_) -* Contributors: Jihoon Lee, Viktor Kunovski, sfalexrog - -0.2.0 (2019-01-30) ------------------- -* Add "default_stream_type" parameter (`#84 `_) - This allows users to specify default stream type in their .launch files. Using a "ros_compressed" stream type sometimes - results in a much lower resource consumption, and having it set as a default is much nicer for end users. -* Add a workaround for MultipartStream constant busy state (`#83 `_) - * Add a workaround for MultipartStream constant busy state - * Remove C++11 features -* lax rule for topic name (`#77 `_) -* Add PngStreamer (`#74 `_) -* fix SteadyTimer check for backported ROS versions (`#71 `_) - i.e. on current kinetic -* Pkg format 2 (`#68 `_) - * use package format 2 - * add missing dependency on sensor_msgs -* fixed undeclared CODEC_FLAG_GLOBAL_HEADER (`#65 `_) -* Contributors: Andreas Klintberg, Dirk Thomas, Felix Ruess, Kazuto Murase, Viktor Kunovski, sfalexrog - -0.1.0 (2018-07-01) ------------------- -* Avoid queuing of images on slow ethernet connection (`#64 `_) -* use SteadyTimer (if available) for cleaning up inactive streams (`#63 `_) - * use SteadyTimer for cleaning up inactive streams - so that cleanup works correctly even if system time changes - SteadyTimer is available since roscpp 1.13.1 - * possibility to use SteadyTimer on older ROS versions - when SteadyTimer has been backported to those... -* Fix segfault in libav_streamer destructor (resolves `#59 `_) (`#60 `_) -* Fix vp8 in kinetic add vp9 and h264 support (`#52 `_) - * fix vp8 in kinetic - * add h264 and vp9 support -* Add Indigo test matrix in travis configuration (`#50 `_) -* Set image streamer as inactive if topic is not available (`#53 `_) - * Resolves `#38 `_ -* Fix Build for ubuntu 14.04 (`#48 `_) - * fix issue `#47 `_ - * fix double free -* Revert "use SteadyTimer for cleaning up inactive streams (`#45 `_)" (`#51 `_) - This reverts commit ae74f19ada22f288a7c7a99ada7a1b9b6037c7ce. -* use SteadyTimer for cleaning up inactive streams (`#45 `_) - so that cleanup works correctly even if system time changes -* Use trusty instead of xenial. See `travis-ci/travis-ci#7260 `_ (`#49 `_) - * Also see `RobotWebTools/rosbridge_suite#311 `_ -* Contributors: Felix Ruess, James Bailey, Jihoon Lee, randoms, schallerr - -0.0.7 (2017-11-20) ------------------- -* Ffmpeg 3 (`#43 `_) - * Correct use of deprecated parameters - codec_context\_->rc_buffer_aggressivity marked as "currently useless", so removed - codec_context\_->frame_skip_threshold access through new priv_data api - * New names for pixel formats - * AVPicture is deprecated, use AVFrame - * Switch to non-deprecated free functions - * Use new encoding api for newer versions - * codec_context is deprecated, use packet flags -* Update travis configuration to test against kinetic (`#44 `_) -* fixed misuse of remove_if (`#35 `_) -* Merge pull request `#33 `_ from achim-k/patch-1 - web_video_server: fix bool function not returning - This fix is required when compiling the package with `clang`. Otherwise a SIGILL (Illegal instruction) is triggered. -* Contributors: Hans-Joachim Krauch, Jan, Jihoon Lee, russelhowe - -0.0.6 (2017-01-17) ------------------- -* Fixed topic list to display all image topics, fixing Issue `#18 `_. -* Contributors: Eric - -0.0.5 (2016-10-13) ------------------- -* Merge pull request `#23 `_ from iki-wgt/develop - More information when server creation is failed -* Removed empty line -* More detailed exception message - Programm behavior is not changed since the exception is rethrown. -* Contributors: BennyRe, Russell Toris - -0.0.4 (2015-08-18) ------------------- -* Merge pull request #16 from mitchellwills/compressed - Adds support for streaming ROS compressed image topics without the need to reencode them -* Switch to checkout async_web_server_cpp from source -* Upgrade for change in signature of async_web_server_cpp request handler -* Added ros compressed video streamer type - This directly passes the ros compressed frame data to the http socket without reencoding it -* Switched from passing image transport to passing node handle to streamer constructors -* Added default transport parameter for regular image streamers -* Contributors: Mitchell Wills, Russell Toris - -0.0.3 (2015-05-07) ------------------- -* added verbose flag -* Contributors: Russell Toris - -0.0.2 (2015-02-20) ------------------- -* Merge pull request #10 from mitchellwills/develop - Added option to specify server address -* Added option to specify server address -* Merge pull request #3 from mitchellwills/develop - Remove old http_server implementation and replace it with async_web_server_cpp package -* Moved from using built in http server to new async_web_server_cpp package -* Did some cleanup of streamers -* Update package.xml -* Contributors: Mitchell Wills, Russell Toris - -0.0.1 (2014-10-30) ------------------- -* missed travis file -* cleanup and travis build -* ROS auto-format -* Merge pull request #1 from mitchellwills/develop - Initial implementation of a http web server that serves ROS image topics as multiple web compatible formats -* Made some changes suggested by catkin_lint and did some package cleanup -* Added support for libavstreamer on Ubuntu 13.10 version of libav -* Added support for specifying vp8 quality parameter -* Implemented lazy initialization for libav buffers so that output size can be infered from the first image -* Updated README -* Added vp8 support -* Broke image encodings out into different files -* Made write operations async - Send timestamps for mjpeg stream -* Initial commit -* Update README.md -* Update README.md -* Update README.md -* Initial commit -* Contributors: Mitchell Wills, Russell Toris diff --git a/web_video_server/CMakeLists.txt b/web_video_server/CMakeLists.txt deleted file mode 100644 index ce84c17..0000000 --- a/web_video_server/CMakeLists.txt +++ /dev/null @@ -1,83 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(web_video_server) - -find_package(ament_cmake_ros REQUIRED) - -find_package(async_web_server_cpp REQUIRED) -find_package(cv_bridge REQUIRED) -find_package(image_transport REQUIRED) -find_package(rclcpp REQUIRED) -find_package(sensor_msgs REQUIRED) - -find_package(OpenCV REQUIRED) -find_package(Boost REQUIRED COMPONENTS thread) - -find_package(PkgConfig REQUIRED) -pkg_check_modules(avcodec libavcodec REQUIRED) -pkg_check_modules(avformat libavformat REQUIRED) -pkg_check_modules(avutil libavutil REQUIRED) -pkg_check_modules(swscale libswscale REQUIRED) - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -################################################### -## Declare things to be passed to other projects ## -################################################### - -########### -## Build ## -########### - -## Specify additional locations of header files -include_directories(include - ${Boost_INCLUDE_DIRS} - ${avcodec_INCLUDE_DIRS} - ${avformat_INCLUDE_DIRS} - ${avutil_INCLUDE_DIRS} - ${swscale_INCLUDE_DIRS} -) - -## Declare a cpp executable -add_executable(${PROJECT_NAME} - src/web_video_server.cpp - src/image_streamer.cpp - src/libav_streamer.cpp - src/vp8_streamer.cpp - src/h264_streamer.cpp - src/vp9_streamer.cpp - src/multipart_stream.cpp - src/ros_compressed_streamer.cpp - src/jpeg_streamers.cpp - src/png_streamers.cpp -) - -ament_target_dependencies(${PROJECT_NAME} - async_web_server_cpp cv_bridge image_transport rclcpp sensor_msgs) - -## Specify libraries to link a library or executable target against -target_link_libraries(${PROJECT_NAME} - ${Boost_LIBRARIES} - ${OpenCV_LIBS} - ${avcodec_LIBRARIES} - ${avformat_LIBRARIES} - ${avutil_LIBRARIES} - ${swscale_LIBRARIES} -) - -############# -## Install ## -############# - -## Mark executables and/or libraries for installation -install(TARGETS ${PROJECT_NAME} - DESTINATION lib/${PROJECT_NAME} -) - -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION include/${PROJECT_NAME} - FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" -) - -ament_package() diff --git a/web_video_server/LICENSE b/web_video_server/LICENSE deleted file mode 100644 index 872a63f..0000000 --- a/web_video_server/LICENSE +++ /dev/null @@ -1,32 +0,0 @@ -Software License Agreement (BSD License) - -Copyright (c) 2014, Worcester Polytechnic Institute -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions -are met: - - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above - copyright notice, this list of conditions and the following - disclaimer in the documentation and/or other materials provided - with the distribution. - * Neither the name of Worcester Polytechnic Institute - nor the names of its contributors may be used to - endorse or promote products derived from this software without - specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. diff --git a/web_video_server/README.md b/web_video_server/README.md deleted file mode 100644 index cbe4568..0000000 --- a/web_video_server/README.md +++ /dev/null @@ -1,17 +0,0 @@ -web_video_server [![Build Status](https://api.travis-ci.org/RobotWebTools/web_video_server.png)](https://travis-ci.org/RobotWebTools/web_video_server) -================ - -#### HTTP Streaming of ROS Image Topics in Multiple Formats -This node combines the capabilities of [ros_web_video](https://github.com/RobotWebTools/ros_web_video) and [mjpeg_server](https://github.com/RobotWebTools/mjpeg_server) into a single node. - -For full documentation, see [the ROS wiki](http://ros.org/wiki/web_video_server). - -[Doxygen](http://docs.ros.org/indigo/api/web_video_server/html/) files can be found on the ROS wiki. - -This project is released as part of the [Robot Web Tools](http://robotwebtools.org/) effort. - -### License -web_video_server is released with a BSD license. For full terms and conditions, see the [LICENSE](LICENSE) file. - -### Authors -See the [AUTHORS](AUTHORS.md) file for a full list of contributors. diff --git a/web_video_server/cam1.yaml b/web_video_server/cam1.yaml deleted file mode 100644 index 1dee962..0000000 --- a/web_video_server/cam1.yaml +++ /dev/null @@ -1,11 +0,0 @@ -/**: - ros__parameters: - video_device: "/dev/video0" - framerate: 10.0 - io_method: "mmap" - frame_id: "cam1" - pixel_format: "yuyv2rgb" - color_format: "yuyv2rgb" - image_width: 320 - image_height: 240 - camera_name: "cam1" diff --git a/web_video_server/include/web_video_server/h264_streamer.h b/web_video_server/include/web_video_server/h264_streamer.h deleted file mode 100644 index 9961389..0000000 --- a/web_video_server/include/web_video_server/h264_streamer.h +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef H264_STREAMERS_H_ -#define H264_STREAMERS_H_ - -#include -#include "web_video_server/libav_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" - -namespace web_video_server -{ - -class H264Streamer : public LibavStreamer -{ -public: - H264Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - ~H264Streamer(); -protected: - virtual void initializeEncoder(); - std::string preset_; -}; - -class H264StreamerType : public LibavStreamerType -{ -public: - H264StreamerType(); - virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); -}; - -} - -#endif - diff --git a/web_video_server/include/web_video_server/image_streamer.h b/web_video_server/include/web_video_server/image_streamer.h deleted file mode 100644 index 59a1a92..0000000 --- a/web_video_server/include/web_video_server/image_streamer.h +++ /dev/null @@ -1,93 +0,0 @@ -#ifndef IMAGE_STREAMER_H_ -#define IMAGE_STREAMER_H_ - -#include -#include -#include -#include -#include "async_web_server_cpp/http_server.hpp" -#include "async_web_server_cpp/http_request.hpp" - -namespace web_video_server -{ - -class ImageStreamer -{ -public: - ImageStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - - virtual void start() = 0; - virtual ~ImageStreamer(); - - bool isInactive() - { - return inactive_; - } - ; - - /** - * Restreams the last received image frame if older than max_age. - */ - virtual void restreamFrame(double max_age) = 0; - - std::string getTopic() - { - return topic_; - } - ; -protected: - async_web_server_cpp::HttpConnectionPtr connection_; - async_web_server_cpp::HttpRequest request_; - rclcpp::Node::SharedPtr nh_; - bool inactive_; - image_transport::Subscriber image_sub_; - std::string topic_; -}; - - -class ImageTransportImageStreamer : public ImageStreamer -{ -public: - ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - virtual ~ImageTransportImageStreamer(); - - virtual void start(); - -protected: - virtual void sendImage(const cv::Mat &, const rclcpp::Time &time) = 0; - virtual void restreamFrame(double max_age); - virtual void initialize(const cv::Mat &); - - image_transport::Subscriber image_sub_; - int output_width_; - int output_height_; - bool invert_; - std::string default_transport_; - - rclcpp::Time last_frame; - cv::Mat output_size_image; - boost::mutex send_mutex_; - -private: - image_transport::ImageTransport it_; - bool initialized_; - - void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &msg); -}; - -class ImageStreamerType -{ -public: - virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) = 0; - - virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0; -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/jpeg_streamers.h b/web_video_server/include/web_video_server/jpeg_streamers.h deleted file mode 100644 index ad788fa..0000000 --- a/web_video_server/include/web_video_server/jpeg_streamers.h +++ /dev/null @@ -1,51 +0,0 @@ -#ifndef JPEG_STREAMERS_H_ -#define JPEG_STREAMERS_H_ - -#include -#include "web_video_server/image_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" -#include "web_video_server/multipart_stream.h" - -namespace web_video_server -{ - -class MjpegStreamer : public ImageTransportImageStreamer -{ -public: - MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - ~MjpegStreamer(); -protected: - virtual void sendImage(const cv::Mat &, const rclcpp::Time &time); - -private: - MultipartStream stream_; - int quality_; -}; - -class MjpegStreamerType : public ImageStreamerType -{ -public: - boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - std::string create_viewer(const async_web_server_cpp::HttpRequest &request); -}; - -class JpegSnapshotStreamer : public ImageTransportImageStreamer -{ -public: - JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh); - ~JpegSnapshotStreamer(); -protected: - virtual void sendImage(const cv::Mat &, const rclcpp::Time &time); - -private: - int quality_; -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/libav_streamer.h b/web_video_server/include/web_video_server/libav_streamer.h deleted file mode 100644 index 643e3b3..0000000 --- a/web_video_server/include/web_video_server/libav_streamer.h +++ /dev/null @@ -1,81 +0,0 @@ -#ifndef LIBAV_STREAMERS_H_ -#define LIBAV_STREAMERS_H_ - -#include -#include "web_video_server/image_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" - -extern "C" -{ -#include -#include -#include -#include -#include -#include -#include -#include -} - -namespace web_video_server -{ - -class LibavStreamer : public ImageTransportImageStreamer -{ -public: - LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh, const std::string &format_name, const std::string &codec_name, - const std::string &content_type); - - ~LibavStreamer(); - -protected: - virtual void initializeEncoder(); - virtual void sendImage(const cv::Mat&, const rclcpp::Time& time); - virtual void initialize(const cv::Mat&); - AVOutputFormat* output_format_; - AVFormatContext* format_context_; - AVCodec* codec_; - AVCodecContext* codec_context_; - AVStream* video_stream_; - - AVDictionary* opt_; // container format options - -private: - AVFrame* frame_; - struct SwsContext* sws_context_; - rclcpp::Time first_image_timestamp_; - boost::mutex encode_mutex_; - - std::string format_name_; - std::string codec_name_; - std::string content_type_; - int bitrate_; - int qmin_; - int qmax_; - int gop_; - - uint8_t* io_buffer_; // custom IO buffer -}; - -class LibavStreamerType : public ImageStreamerType -{ -public: - LibavStreamerType(const std::string &format_name, const std::string &codec_name, const std::string &content_type); - - boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - - std::string create_viewer(const async_web_server_cpp::HttpRequest &request); - -private: - const std::string format_name_; - const std::string codec_name_; - const std::string content_type_; -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/multipart_stream.h b/web_video_server/include/web_video_server/multipart_stream.h deleted file mode 100644 index d6ea359..0000000 --- a/web_video_server/include/web_video_server/multipart_stream.h +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef MULTIPART_STREAM_H_ -#define MULTIPART_STREAM_H_ - -#include -#include - -#include - -namespace web_video_server -{ - -struct PendingFooter { - rclcpp::Time timestamp; - std::weak_ptr contents; -}; - -class MultipartStream { -public: - MultipartStream(std::function get_now, - async_web_server_cpp::HttpConnectionPtr& connection, - const std::string& boundry="boundarydonotcross", - std::size_t max_queue_size=1); - - void sendInitialHeader(); - void sendPartHeader(const rclcpp::Time &time, const std::string& type, size_t payload_size); - void sendPartFooter(const rclcpp::Time &time); - void sendPartAndClear(const rclcpp::Time &time, const std::string& type, std::vector &data); - void sendPart(const rclcpp::Time &time, const std::string& type, const boost::asio::const_buffer &buffer, - async_web_server_cpp::HttpConnection::ResourcePtr resource); - -private: - bool isBusy(); - -private: - std::function get_now_; - const std::size_t max_queue_size_; - async_web_server_cpp::HttpConnectionPtr connection_; - std::string boundry_; - std::queue pending_footers_; -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/png_streamers.h b/web_video_server/include/web_video_server/png_streamers.h deleted file mode 100644 index a6edabc..0000000 --- a/web_video_server/include/web_video_server/png_streamers.h +++ /dev/null @@ -1,51 +0,0 @@ -#ifndef PNG_STREAMERS_H_ -#define PNG_STREAMERS_H_ - -#include -#include "web_video_server/image_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" -#include "web_video_server/multipart_stream.h" - -namespace web_video_server -{ - -class PngStreamer : public ImageTransportImageStreamer -{ -public: - PngStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - ~PngStreamer(); -protected: - virtual void sendImage(const cv::Mat &, const rclcpp::Time &time); - -private: - MultipartStream stream_; - int quality_; -}; - -class PngStreamerType : public ImageStreamerType -{ -public: - boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - std::string create_viewer(const async_web_server_cpp::HttpRequest &request); -}; - -class PngSnapshotStreamer : public ImageTransportImageStreamer -{ -public: - PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh); - ~PngSnapshotStreamer(); -protected: - virtual void sendImage(const cv::Mat &, const rclcpp::Time &time); - -private: - int quality_; -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/ros_compressed_streamer.h b/web_video_server/include/web_video_server/ros_compressed_streamer.h deleted file mode 100644 index 7219dfd..0000000 --- a/web_video_server/include/web_video_server/ros_compressed_streamer.h +++ /dev/null @@ -1,45 +0,0 @@ -#ifndef ROS_COMPRESSED_STREAMERS_H_ -#define ROS_COMPRESSED_STREAMERS_H_ - -#include -#include "web_video_server/image_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" -#include "web_video_server/multipart_stream.h" - -namespace web_video_server -{ - -class RosCompressedStreamer : public ImageStreamer -{ -public: - RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - ~RosCompressedStreamer(); - virtual void start(); - virtual void restreamFrame(double max_age); - -protected: - virtual void sendImage(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg, const rclcpp::Time &time); - -private: - void imageCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg); - MultipartStream stream_; - rclcpp::Subscription::SharedPtr image_sub_; - rclcpp::Time last_frame; - sensor_msgs::msg::CompressedImage::ConstSharedPtr last_msg; - boost::mutex send_mutex_; -}; - -class RosCompressedStreamerType : public ImageStreamerType -{ -public: - boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - std::string create_viewer(const async_web_server_cpp::HttpRequest &request); -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/vp8_streamer.h b/web_video_server/include/web_video_server/vp8_streamer.h deleted file mode 100644 index 46e8bed..0000000 --- a/web_video_server/include/web_video_server/vp8_streamer.h +++ /dev/null @@ -1,72 +0,0 @@ -/********************************************************************* - * - * Software License Agreement (BSD License) - * - * Copyright (c) 2014, Worcester Polytechnic Institute - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Worcester Polytechnic Institute nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - *********************************************************************/ - -#ifndef VP8_STREAMERS_H_ -#define VP8_STREAMERS_H_ - -#include -#include "web_video_server/libav_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" - -namespace web_video_server -{ - -class Vp8Streamer : public LibavStreamer -{ -public: - Vp8Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - ~Vp8Streamer(); -protected: - virtual void initializeEncoder(); -private: - std::string quality_; -}; - -class Vp8StreamerType : public LibavStreamerType -{ -public: - Vp8StreamerType(); - virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); -}; - -} - -#endif - diff --git a/web_video_server/include/web_video_server/vp9_streamer.h b/web_video_server/include/web_video_server/vp9_streamer.h deleted file mode 100644 index 06c48f8..0000000 --- a/web_video_server/include/web_video_server/vp9_streamer.h +++ /dev/null @@ -1,33 +0,0 @@ -#ifndef VP9_STREAMERS_H_ -#define VP9_STREAMERS_H_ - -#include -#include "web_video_server/libav_streamer.h" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" - -namespace web_video_server -{ - -class Vp9Streamer : public LibavStreamer -{ -public: - Vp9Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); - ~Vp9Streamer(); -protected: - virtual void initializeEncoder(); -}; - -class Vp9StreamerType : public LibavStreamerType -{ -public: - Vp9StreamerType(); - virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh); -}; - -} - -#endif diff --git a/web_video_server/include/web_video_server/web_video_server.h b/web_video_server/include/web_video_server/web_video_server.h deleted file mode 100644 index 1da6015..0000000 --- a/web_video_server/include/web_video_server/web_video_server.h +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef WEB_VIDEO_SERVER_H_ -#define WEB_VIDEO_SERVER_H_ - -#include -#include -#include -#include "web_video_server/image_streamer.h" -#include "async_web_server_cpp/http_server.hpp" -#include "async_web_server_cpp/http_request.hpp" -#include "async_web_server_cpp/http_connection.hpp" - -namespace web_video_server -{ - -/** - * @class WebVideoServer - * @brief - */ -class WebVideoServer -{ -public: - /** - * @brief Constructor - * @return - */ - WebVideoServer(rclcpp::Node::SharedPtr &nh, rclcpp::Node::SharedPtr &private_nh); - - /** - * @brief Destructor - Cleans up - */ - virtual ~WebVideoServer(); - - /** - * @brief Starts the server and spins - */ - void spin(); - - void setup_cleanup_inactive_streams(); - - bool handle_stream(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - - bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - - bool handle_snapshot(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - - bool handle_list_streams(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end); - -private: - void restreamFrames(double max_age); - void cleanup_inactive_streams(); - - rclcpp::Node::SharedPtr nh_; - rclcpp::WallTimer::SharedPtr cleanup_timer_; - int ros_threads_; - double publish_rate_; - int port_; - std::string address_; - boost::shared_ptr server_; - async_web_server_cpp::HttpRequestHandlerGroup handler_group_; - - std::vector > image_subscribers_; - std::map > stream_types_; - boost::mutex subscriber_mutex_; -}; - -} - -#endif diff --git a/web_video_server/mainpage.dox b/web_video_server/mainpage.dox deleted file mode 100644 index dd3a32b..0000000 --- a/web_video_server/mainpage.dox +++ /dev/null @@ -1,6 +0,0 @@ -/** -\mainpage - -\b A ROS Node to Stream Image Topics Via multiple formats including MJPEG and VP8 -web_video_server converts ROS image streams into an MJPEG or other encoding and streams them via a socket connection. -*/ diff --git a/web_video_server/package.xml b/web_video_server/package.xml deleted file mode 100644 index 6e3a11c..0000000 --- a/web_video_server/package.xml +++ /dev/null @@ -1,35 +0,0 @@ - - - web_video_server - 1.0.0 - HTTP Streaming of ROS Image Topics in Multiple Formats - - Russell Toris - Mitchell Wills - - BSD - - http://ros.org/wiki/web_video_server - https://github.com/RobotWebTools/web_video_server/issues - https://github.com/RobotWebTools/web_video_server - - ament_cmake_ros - - rclcpp - cv_bridge - image_transport - async_web_server_cpp - ffmpeg - sensor_msgs - - rclcpp - cv_bridge - image_transport - async_web_server_cpp - ffmpeg - sensor_msgs - - - ament_cmake - - diff --git a/web_video_server/src/h264_streamer.cpp b/web_video_server/src/h264_streamer.cpp deleted file mode 100644 index a866aa1..0000000 --- a/web_video_server/src/h264_streamer.cpp +++ /dev/null @@ -1,49 +0,0 @@ -#include "web_video_server/h264_streamer.h" - -namespace web_video_server -{ - -H264Streamer::H264Streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - LibavStreamer(request, connection, nh, "mp4", "libx264", "video/mp4") -{ - /* possible quality presets: - * ultrafast, superfast, veryfast, faster, fast, medium, slow, slower, veryslow, placebo - * no latency improvements observed with ultrafast instead of medium - */ - preset_ = request.get_query_param_value_or_default("preset", "ultrafast"); -} - -H264Streamer::~H264Streamer() -{ -} - -void H264Streamer::initializeEncoder() -{ - av_opt_set(codec_context_->priv_data, "preset", preset_.c_str(), 0); - av_opt_set(codec_context_->priv_data, "tune", "zerolatency", 0); - av_opt_set_int(codec_context_->priv_data, "crf", 20, 0); - av_opt_set_int(codec_context_->priv_data, "bufsize", 100, 0); - av_opt_set_int(codec_context_->priv_data, "keyint", 30, 0); - av_opt_set_int(codec_context_->priv_data, "g", 1, 0); - - // container format options - if (!strcmp(format_context_->oformat->name, "mp4")) { - // set up mp4 for streaming (instead of seekable file output) - av_dict_set(&opt_, "movflags", "+frag_keyframe+empty_moov+faststart", 0); - } -} - -H264StreamerType::H264StreamerType() : - LibavStreamerType("mp4", "libx264", "video/mp4") -{ -} - -boost::shared_ptr H264StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr(new H264Streamer(request, connection, nh)); -} - -} diff --git a/web_video_server/src/image_streamer.cpp b/web_video_server/src/image_streamer.cpp deleted file mode 100644 index 05012c2..0000000 --- a/web_video_server/src/image_streamer.cpp +++ /dev/null @@ -1,192 +0,0 @@ -#include "web_video_server/image_streamer.h" -#include -#include - -namespace web_video_server -{ - -ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - request_(request), connection_(connection), nh_(nh), inactive_(false) -{ - topic_ = request.get_query_param_value_or_default("topic", ""); -} - -ImageStreamer::~ImageStreamer() -{ -} - -ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - ImageStreamer(request, connection, nh), it_(nh), initialized_(false) -{ - output_width_ = request.get_query_param_value_or_default("width", -1); - output_height_ = request.get_query_param_value_or_default("height", -1); - invert_ = request.has_query_param("invert"); - default_transport_ = request.get_query_param_value_or_default("default_transport", "raw"); -} - -ImageTransportImageStreamer::~ImageTransportImageStreamer() -{ -} - -void ImageTransportImageStreamer::start() -{ - image_transport::TransportHints hints(nh_.get(), default_transport_); - auto tnat = nh_->get_topic_names_and_types(); - inactive_ = true; - for (auto topic_and_types : tnat) { - if (topic_and_types.second.size() > 1) { - // explicitly avoid topics with more than one type - break; - } - auto & topic_name = topic_and_types.first; - if(topic_name == topic_ || (topic_name.find("/") == 0 && topic_name.substr(1) == topic_)){ - inactive_ = false; - break; - } - } - image_sub_ = it_.subscribe(topic_, 1, &ImageTransportImageStreamer::imageCallback, this, &hints); -} - -void ImageTransportImageStreamer::initialize(const cv::Mat &) -{ -} - -void ImageTransportImageStreamer::restreamFrame(double max_age) -{ - if (inactive_ || !initialized_ ) - return; - try { - if ( last_frame + rclcpp::Duration::from_seconds(max_age) < nh_->now() ) { - boost::mutex::scoped_lock lock(send_mutex_); - sendImage(output_size_image, nh_->now() ); // don't update last_frame, it may remain an old value. - } - } - catch (boost::system::system_error &e) - { - // happens when client disconnects - RCLCPP_DEBUG(nh_->get_logger(), "system_error exception: %s", e.what()); - inactive_ = true; - return; - } - catch (std::exception &e) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "exception: %s", e.what()); - inactive_ = true; - return; - } - catch (...) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "exception"); - inactive_ = true; - return; - } -} - -void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &msg) -{ - if (inactive_) - return; - - cv::Mat img; - try - { - if (msg->encoding.find("F") != std::string::npos) - { - // scale floating point images - cv::Mat float_image_bridge = cv_bridge::toCvCopy(msg, msg->encoding)->image; - cv::Mat_ float_image = float_image_bridge; - double max_val; - cv::minMaxIdx(float_image, 0, &max_val); - - if (max_val > 0) - { - float_image *= (255 / max_val); - } - img = float_image; - } - else - { - // Convert to OpenCV native BGR color - img = cv_bridge::toCvCopy(msg, "bgr8")->image; - } - - int input_width = img.cols; - int input_height = img.rows; - - if (output_width_ == -1) - output_width_ = input_width; - if (output_height_ == -1) - output_height_ = input_height; - - if (invert_) - { - // Rotate 180 degrees - cv::flip(img, img, false); - cv::flip(img, img, true); - } - - boost::mutex::scoped_lock lock(send_mutex_); // protects output_size_image - if (output_width_ != input_width || output_height_ != input_height) - { - cv::Mat img_resized; - cv::Size new_size(output_width_, output_height_); - cv::resize(img, img_resized, new_size); - output_size_image = img_resized; - } - else - { - output_size_image = img; - } - - if (!initialized_) - { - initialize(output_size_image); - initialized_ = true; - } - - last_frame = nh_->now(); - sendImage(output_size_image, last_frame ); - - } - catch (cv_bridge::Exception &e) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "cv_bridge exception: %s", e.what()); - inactive_ = true; - return; - } - catch (cv::Exception &e) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "cv_bridge exception: %s", e.what()); - inactive_ = true; - return; - } - catch (boost::system::system_error &e) - { - // happens when client disconnects - RCLCPP_DEBUG(nh_->get_logger(), "system_error exception: %s", e.what()); - inactive_ = true; - return; - } - catch (std::exception &e) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "exception: %s", e.what()); - inactive_ = true; - return; - } - catch (...) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "exception"); - inactive_ = true; - return; - } -} - -} diff --git a/web_video_server/src/jpeg_streamers.cpp b/web_video_server/src/jpeg_streamers.cpp deleted file mode 100644 index 0c5cf88..0000000 --- a/web_video_server/src/jpeg_streamers.cpp +++ /dev/null @@ -1,91 +0,0 @@ -#include "web_video_server/jpeg_streamers.h" -#include "async_web_server_cpp/http_reply.hpp" - -namespace web_video_server -{ - -MjpegStreamer::MjpegStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - ImageTransportImageStreamer(request, connection, nh), stream_(std::bind(&rclcpp::Node::now, nh), connection) -{ - quality_ = request.get_query_param_value_or_default("quality", 95); - stream_.sendInitialHeader(); -} - -MjpegStreamer::~MjpegStreamer() -{ - this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. -} - -void MjpegStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) -{ - std::vector encode_params; - encode_params.push_back(cv::IMWRITE_JPEG_QUALITY); - encode_params.push_back(quality_); - - std::vector encoded_buffer; - cv::imencode(".jpeg", img, encoded_buffer, encode_params); - - stream_.sendPartAndClear(time, "image/jpeg", encoded_buffer); -} - -boost::shared_ptr MjpegStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr(new MjpegStreamer(request, connection, nh)); -} - -std::string MjpegStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) -{ - std::stringstream ss; - ss << ""; - return ss.str(); -} - -JpegSnapshotStreamer::JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) : - ImageTransportImageStreamer(request, connection, nh) -{ - quality_ = request.get_query_param_value_or_default("quality", 95); -} - -JpegSnapshotStreamer::~JpegSnapshotStreamer() -{ - this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. -} - -void JpegSnapshotStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) -{ - std::vector encode_params; - encode_params.push_back(cv::IMWRITE_JPEG_QUALITY); - encode_params.push_back(quality_); - - std::vector encoded_buffer; - cv::imencode(".jpeg", img, encoded_buffer, encode_params); - - char stamp[20]; - sprintf(stamp, "%.06lf", time.seconds()); - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok) - .header("Connection", "close") - .header("Server", "web_video_server") - .header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, " - "max-age=0") - .header("X-Timestamp", stamp) - .header("Pragma", "no-cache") - .header("Content-type", "image/jpeg") - .header("Access-Control-Allow-Origin", "*") - .header("Content-Length", - boost::lexical_cast(encoded_buffer.size())) - .write(connection_); - connection_->write_and_clear(encoded_buffer); - inactive_ = true; -} - -} diff --git a/web_video_server/src/libav_streamer.cpp b/web_video_server/src/libav_streamer.cpp deleted file mode 100644 index 28d0425..0000000 --- a/web_video_server/src/libav_streamer.cpp +++ /dev/null @@ -1,383 +0,0 @@ -#include "web_video_server/libav_streamer.h" -#include "async_web_server_cpp/http_reply.hpp" - -/*https://stackoverflow.com/questions/46884682/error-in-building-opencv-with-ffmpeg*/ -#define AV_CODEC_FLAG_GLOBAL_HEADER (1 << 22) -#define CODEC_FLAG_GLOBAL_HEADER AV_CODEC_FLAG_GLOBAL_HEADER - -namespace web_video_server -{ - -static int ffmpeg_boost_mutex_lock_manager(void **mutex, enum AVLockOp op) -{ - if (NULL == mutex) - return -1; - - switch (op) - { - case AV_LOCK_CREATE: - { - *mutex = NULL; - boost::mutex *m = new boost::mutex(); - *mutex = static_cast(m); - break; - } - case AV_LOCK_OBTAIN: - { - boost::mutex *m = static_cast(*mutex); - m->lock(); - break; - } - case AV_LOCK_RELEASE: - { - boost::mutex *m = static_cast(*mutex); - m->unlock(); - break; - } - case AV_LOCK_DESTROY: - { - boost::mutex *m = static_cast(*mutex); - m->lock(); - m->unlock(); - delete m; - break; - } - default: - break; - } - return 0; -} - -LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh, - const std::string &format_name, const std::string &codec_name, - const std::string &content_type) : - ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( - 0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_( - format_name), codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0) -{ - - bitrate_ = request.get_query_param_value_or_default("bitrate", 100000); - qmin_ = request.get_query_param_value_or_default("qmin", 10); - qmax_ = request.get_query_param_value_or_default("qmax", 42); - gop_ = request.get_query_param_value_or_default("gop", 250); - - av_lockmgr_register(&ffmpeg_boost_mutex_lock_manager); - av_register_all(); -} - -LibavStreamer::~LibavStreamer() -{ - if (codec_context_) - avcodec_close(codec_context_); - if (frame_) - { -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - av_free(frame_); - frame_ = NULL; -#else - av_frame_free(&frame_); -#endif - } - if (io_buffer_) - delete io_buffer_; - if (format_context_) { - if (format_context_->pb) - av_free(format_context_->pb); - avformat_free_context(format_context_); - } - if (sws_context_) - sws_freeContext(sws_context_); -} - -// output callback for ffmpeg IO context -static int dispatch_output_packet(void* opaque, uint8_t* buffer, int buffer_size) -{ - async_web_server_cpp::HttpConnectionPtr connection = *((async_web_server_cpp::HttpConnectionPtr*) opaque); - std::vector encoded_frame; - encoded_frame.assign(buffer, buffer + buffer_size); - connection->write_and_clear(encoded_frame); - return 0; // TODO: can this fail? -} - -void LibavStreamer::initialize(const cv::Mat &img) -{ - // Load format - format_context_ = avformat_alloc_context(); - if (!format_context_) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error allocating ffmpeg format context"); - } - output_format_ = av_guess_format(format_name_.c_str(), NULL, NULL); - if (!output_format_) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error looking up output format"); - } - format_context_->oformat = output_format_; - - // Set up custom IO callback. - size_t io_buffer_size = 3 * 1024; // 3M seen elsewhere and adjudged good - io_buffer_ = new unsigned char[io_buffer_size]; - AVIOContext* io_ctx = avio_alloc_context(io_buffer_, io_buffer_size, AVIO_FLAG_WRITE, &connection_, NULL, dispatch_output_packet, NULL); - if (!io_ctx) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error setting up IO context"); - } - io_ctx->seekable = 0; // no seeking, it's a stream - format_context_->pb = io_ctx; - output_format_->flags |= AVFMT_FLAG_CUSTOM_IO; - output_format_->flags |= AVFMT_NOFILE; - - // Load codec - if (codec_name_.empty()) // use default codec if none specified - codec_ = avcodec_find_encoder(output_format_->video_codec); - else - codec_ = avcodec_find_encoder_by_name(codec_name_.c_str()); - if (!codec_) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error looking up codec"); - } - video_stream_ = avformat_new_stream(format_context_, codec_); - if (!video_stream_) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error creating video stream"); - } - codec_context_ = video_stream_->codec; - - // Set options - avcodec_get_context_defaults3(codec_context_, codec_); - - codec_context_->codec_id = codec_->id; - codec_context_->bit_rate = bitrate_; - - codec_context_->width = output_width_; - codec_context_->height = output_height_; - codec_context_->delay = 0; - - video_stream_->time_base.num = 1; - video_stream_->time_base.den = 1000; - - codec_context_->time_base.num = 1; - codec_context_->time_base.den = 1; - codec_context_->gop_size = gop_; - codec_context_->pix_fmt = AV_PIX_FMT_YUV420P; - codec_context_->max_b_frames = 0; - - // Quality settings - codec_context_->qmin = qmin_; - codec_context_->qmax = qmax_; - - initializeEncoder(); - - // Some formats want stream headers to be separate - if (format_context_->oformat->flags & AVFMT_GLOBALHEADER) - codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER; - - // Open Codec - if (avcodec_open2(codec_context_, codec_, NULL) < 0) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Could not open video codec"); - } - - // Allocate frame buffers -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - frame_ = avcodec_alloc_frame(); -#else - frame_ = av_frame_alloc(); -#endif - av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_, - codec_context_->pix_fmt, 1); - - frame_->width = output_width_; - frame_->height = output_height_; - frame_->format = codec_context_->pix_fmt; - output_format_->flags |= AVFMT_NOFILE; - - // Generate header - std::vector header_buffer; - std::size_t header_size; - uint8_t *header_raw_buffer; - // define meta data - av_dict_set(&format_context_->metadata, "author", "ROS web_video_server", 0); - av_dict_set(&format_context_->metadata, "title", topic_.c_str(), 0); - - // Send response headers - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( - "Pragma", "no-cache").header("Expires", "0").header("Max-Age", "0").header("Trailer", "Expires").header( - "Content-type", content_type_).header("Access-Control-Allow-Origin", "*").write(connection_); - - // Send video stream header - if (avformat_write_header(format_context_, &opt_) < 0) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error openning dynamic buffer"); - } -} - -void LibavStreamer::initializeEncoder() -{ -} - -void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) -{ - boost::mutex::scoped_lock lock(encode_mutex_); - if (0 == first_image_timestamp_.nanoseconds()) - { - first_image_timestamp_ = time; - } - std::vector encoded_frame; -#if (LIBAVUTIL_VERSION_MAJOR < 53) - PixelFormat input_coding_format = PIX_FMT_BGR24; -#else - AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24; -#endif - -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - AVPicture *raw_frame = new AVPicture; - avpicture_fill(raw_frame, img.data, input_coding_format, output_width_, output_height_); -#else - AVFrame *raw_frame = av_frame_alloc(); - av_image_fill_arrays(raw_frame->data, raw_frame->linesize, - img.data, input_coding_format, output_width_, output_height_, 1); -#endif - - - - // Convert from opencv to libav - if (!sws_context_) - { - static int sws_flags = SWS_BICUBIC; - sws_context_ = sws_getContext(output_width_, output_height_, input_coding_format, output_width_, output_height_, - codec_context_->pix_fmt, sws_flags, NULL, NULL, NULL); - if (!sws_context_) - { - throw std::runtime_error("Could not initialize the conversion context"); - } - } - - - int ret = sws_scale(sws_context_, - (const uint8_t * const *)raw_frame->data, raw_frame->linesize, 0, - output_height_, frame_->data, frame_->linesize); - -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - delete raw_frame; -#else - av_frame_free(&raw_frame); -#endif - - // Encode the frame - AVPacket pkt; - int got_packet; - av_init_packet(&pkt); - -#if (LIBAVCODEC_VERSION_MAJOR < 54) - int buf_size = 6 * output_width_ * output_height_; - pkt.data = (uint8_t*)av_malloc(buf_size); - pkt.size = avcodec_encode_video(codec_context_, pkt.data, buf_size, frame_); - got_packet = pkt.size > 0; -#elif (LIBAVCODEC_VERSION_MAJOR < 57) - pkt.data = NULL; // packet data will be allocated by the encoder - pkt.size = 0; - if (avcodec_encode_video2(codec_context_, &pkt, frame_, &got_packet) < 0) - { - throw std::runtime_error("Error encoding video frame"); - } -#else - pkt.data = NULL; // packet data will be allocated by the encoder - pkt.size = 0; - if (avcodec_send_frame(codec_context_, frame_) < 0) - { - throw std::runtime_error("Error encoding video frame"); - } - if (avcodec_receive_packet(codec_context_, &pkt) < 0) - { - throw std::runtime_error("Error retrieving encoded packet"); - } -#endif - - if (got_packet) - { - std::size_t size; - uint8_t *output_buf; - - double seconds = (time - first_image_timestamp_).seconds(); - // Encode video at 1/0.95 to minimize delay - pkt.pts = (int64_t)(seconds / av_q2d(video_stream_->time_base) * 0.95); - if (pkt.pts <= 0) - pkt.pts = 1; - pkt.dts = AV_NOPTS_VALUE; - - if (pkt.flags&AV_PKT_FLAG_KEY) - pkt.flags |= AV_PKT_FLAG_KEY; - - pkt.stream_index = video_stream_->index; - - if (av_write_frame(format_context_, &pkt)) - { - throw std::runtime_error("Error when writing frame"); - } - } - else - { - encoded_frame.clear(); - } -#if LIBAVCODEC_VERSION_INT < 54 - av_free(pkt.data); -#endif - -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - av_free_packet(&pkt); -#else - av_packet_unref(&pkt); -#endif - - connection_->write_and_clear(encoded_frame); -} - -LibavStreamerType::LibavStreamerType(const std::string &format_name, const std::string &codec_name, - const std::string &content_type) : - format_name_(format_name), codec_name_(codec_name), content_type_(content_type) -{ -} - -boost::shared_ptr LibavStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr( - new LibavStreamer(request, connection, nh, format_name_, codec_name_, content_type_)); -} - -std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) -{ - std::stringstream ss; - ss << ""; - return ss.str(); -} - -} diff --git a/web_video_server/src/multipart_stream.cpp b/web_video_server/src/multipart_stream.cpp deleted file mode 100644 index caf60b7..0000000 --- a/web_video_server/src/multipart_stream.cpp +++ /dev/null @@ -1,84 +0,0 @@ -#include "web_video_server/multipart_stream.h" -#include "async_web_server_cpp/http_reply.hpp" - -namespace web_video_server -{ - -MultipartStream::MultipartStream( - std::function get_now, - async_web_server_cpp::HttpConnectionPtr& connection, - const std::string& boundry, - std::size_t max_queue_size) - : get_now_(get_now), connection_(connection), boundry_(boundry), max_queue_size_(max_queue_size) -{} - -void MultipartStream::sendInitialHeader() { - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( - "Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary="+boundry_).header( - "Access-Control-Allow-Origin", "*").write(connection_); - connection_->write("--"+boundry_+"\r\n"); -} - -void MultipartStream::sendPartHeader(const rclcpp::Time &time, const std::string& type, size_t payload_size) { - char stamp[20]; - sprintf(stamp, "%.06lf", time.seconds()); - std::shared_ptr > headers( - new std::vector()); - headers->push_back(async_web_server_cpp::HttpHeader("Content-type", type)); - headers->push_back(async_web_server_cpp::HttpHeader("X-Timestamp", stamp)); - headers->push_back( - async_web_server_cpp::HttpHeader("Content-Length", boost::lexical_cast(payload_size))); - connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers); -} - -void MultipartStream::sendPartFooter(const rclcpp::Time &time) { - std::shared_ptr str(new std::string("\r\n--"+boundry_+"\r\n")); - PendingFooter pf; - pf.timestamp = time; - pf.contents = str; - connection_->write(boost::asio::buffer(*str), str); - if (max_queue_size_ > 0) pending_footers_.push(pf); -} - -void MultipartStream::sendPartAndClear(const rclcpp::Time &time, const std::string& type, - std::vector &data) { - if (!isBusy()) - { - sendPartHeader(time, type, data.size()); - connection_->write_and_clear(data); - sendPartFooter(time); - } -} - -void MultipartStream::sendPart(const rclcpp::Time &time, const std::string& type, - const boost::asio::const_buffer &buffer, - async_web_server_cpp::HttpConnection::ResourcePtr resource) { - if (!isBusy()) - { - sendPartHeader(time, type, boost::asio::buffer_size(buffer)); - connection_->write(buffer, resource); - sendPartFooter(time); - } -} - -bool MultipartStream::isBusy() { - rclcpp::Time currentTime = get_now_(); - while (!pending_footers_.empty()) - { - if (pending_footers_.front().contents.expired()) { - pending_footers_.pop(); - } else { - rclcpp::Time footerTime = pending_footers_.front().timestamp; - if ((currentTime - footerTime).seconds() > 0.5) { - pending_footers_.pop(); - } else { - break; - } - } - } - return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_); -} - -} diff --git a/web_video_server/src/png_streamers.cpp b/web_video_server/src/png_streamers.cpp deleted file mode 100644 index 1a9f874..0000000 --- a/web_video_server/src/png_streamers.cpp +++ /dev/null @@ -1,91 +0,0 @@ -#include "web_video_server/png_streamers.h" -#include "async_web_server_cpp/http_reply.hpp" - -namespace web_video_server -{ - -PngStreamer::PngStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - ImageTransportImageStreamer(request, connection, nh), stream_(std::bind(&rclcpp::Node::now, nh), connection) -{ - quality_ = request.get_query_param_value_or_default("quality", 3); - stream_.sendInitialHeader(); -} - -PngStreamer::~PngStreamer() -{ - this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. -} - -void PngStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) -{ - std::vector encode_params; - encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION); - encode_params.push_back(quality_); - - std::vector encoded_buffer; - cv::imencode(".png", img, encoded_buffer, encode_params); - - stream_.sendPartAndClear(time, "image/png", encoded_buffer); -} - -boost::shared_ptr PngStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr(new PngStreamer(request, connection, nh)); -} - -std::string PngStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) -{ - std::stringstream ss; - ss << ""; - return ss.str(); -} - -PngSnapshotStreamer::PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) : - ImageTransportImageStreamer(request, connection, nh) -{ - quality_ = request.get_query_param_value_or_default("quality", 3); -} - -PngSnapshotStreamer::~PngSnapshotStreamer() -{ - this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. -} - -void PngSnapshotStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) -{ - std::vector encode_params; - encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION); - encode_params.push_back(quality_); - - std::vector encoded_buffer; - cv::imencode(".png", img, encoded_buffer, encode_params); - - char stamp[20]; - sprintf(stamp, "%.06lf", time.seconds()); - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok) - .header("Connection", "close") - .header("Server", "web_video_server") - .header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, " - "max-age=0") - .header("X-Timestamp", stamp) - .header("Pragma", "no-cache") - .header("Content-type", "image/png") - .header("Access-Control-Allow-Origin", "*") - .header("Content-Length", - boost::lexical_cast(encoded_buffer.size())) - .write(connection_); - connection_->write_and_clear(encoded_buffer); - inactive_ = true; -} - -} diff --git a/web_video_server/src/ros_compressed_streamer.cpp b/web_video_server/src/ros_compressed_streamer.cpp deleted file mode 100644 index 0fedaae..0000000 --- a/web_video_server/src/ros_compressed_streamer.cpp +++ /dev/null @@ -1,102 +0,0 @@ -#include "web_video_server/ros_compressed_streamer.h" - -namespace web_video_server -{ - -RosCompressedStreamer::RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - ImageStreamer(request, connection, nh), stream_(std::bind(&rclcpp::Node::now, nh), connection) -{ - stream_.sendInitialHeader(); -} - -RosCompressedStreamer::~RosCompressedStreamer() -{ - this->inactive_ = true; - boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage. -} - -void RosCompressedStreamer::start() { - std::string compressed_topic = topic_ + "/compressed"; - image_sub_ = nh_->create_subscription( - compressed_topic, 1, std::bind(&RosCompressedStreamer::imageCallback, this, std::placeholders::_1)); -} - -void RosCompressedStreamer::restreamFrame(double max_age) -{ - if (inactive_ || (last_msg == 0)) - return; - - if ( last_frame + rclcpp::Duration::from_seconds(max_age) < nh_->now() ) { - boost::mutex::scoped_lock lock(send_mutex_); - sendImage(last_msg, nh_->now() ); // don't update last_frame, it may remain an old value. - } -} - -void RosCompressedStreamer::sendImage(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg, - const rclcpp::Time &time) { - try { - std::string content_type; - if(msg->format.find("jpeg") != std::string::npos) { - content_type = "image/jpeg"; - } - else if(msg->format.find("png") != std::string::npos) { - content_type = "image/png"; - } - else { - RCLCPP_WARN(nh_->get_logger(), "Unknown ROS compressed image format: %s", msg->format.c_str()); - return; - } - - stream_.sendPart(time, content_type, boost::asio::buffer(msg->data), msg); - } - catch (boost::system::system_error &e) - { - // happens when client disconnects - RCLCPP_DEBUG(nh_->get_logger(), "system_error exception: %s", e.what()); - inactive_ = true; - return; - } - catch (std::exception &e) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "exception: %s", e.what()); - inactive_ = true; - return; - } - catch (...) - { - // TODO THROTTLE with 30 - RCLCPP_ERROR(nh_->get_logger(), "exception"); - inactive_ = true; - return; - } -} - - -void RosCompressedStreamer::imageCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg) { - boost::mutex::scoped_lock lock(send_mutex_); // protects last_msg and last_frame - last_msg = msg; - last_frame = rclcpp::Time(msg->header.stamp); - sendImage(last_msg, last_frame); -} - - -boost::shared_ptr RosCompressedStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr(new RosCompressedStreamer(request, connection, nh)); -} - -std::string RosCompressedStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request) -{ - std::stringstream ss; - ss << ""; - return ss.str(); -} - - -} diff --git a/web_video_server/src/vp8_streamer.cpp b/web_video_server/src/vp8_streamer.cpp deleted file mode 100644 index f45b7ca..0000000 --- a/web_video_server/src/vp8_streamer.cpp +++ /dev/null @@ -1,91 +0,0 @@ -/********************************************************************* - * - * Software License Agreement (BSD License) - * - * Copyright (c) 2014, Worcester Polytechnic Institute - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Worcester Polytechnic Institute nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - *********************************************************************/ - -#include "web_video_server/vp8_streamer.h" - -namespace web_video_server -{ - -Vp8Streamer::Vp8Streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - LibavStreamer(request, connection, nh, "webm", "libvpx", "video/webm") -{ - quality_ = request.get_query_param_value_or_default("quality", "realtime"); -} -Vp8Streamer::~Vp8Streamer() -{ -} - -void Vp8Streamer::initializeEncoder() -{ - typedef std::map AvOptMap; - AvOptMap av_opt_map; - av_opt_map["quality"] = quality_; - av_opt_map["deadline"] = "1"; - av_opt_map["auto-alt-ref"] = "0"; - av_opt_map["lag-in-frames"] = "1"; - av_opt_map["rc_lookahead"] = "1"; - av_opt_map["drop_frame"] = "1"; - av_opt_map["error-resilient"] = "1"; - - for (AvOptMap::iterator itr = av_opt_map.begin(); itr != av_opt_map.end(); ++itr) - { - av_opt_set(codec_context_->priv_data, itr->first.c_str(), itr->second.c_str(), 0); - } - - // Buffering settings - int bufsize = 10; - codec_context_->rc_buffer_size = bufsize; - codec_context_->rc_initial_buffer_occupancy = bufsize; //bitrate/3; - av_opt_set_int(codec_context_->priv_data, "bufsize", bufsize, 0); - av_opt_set_int(codec_context_->priv_data, "buf-initial", bufsize, 0); - av_opt_set_int(codec_context_->priv_data, "buf-optimal", bufsize, 0); - av_opt_set_int(codec_context_->priv_data, "skip_threshold", 10, 0); -} - -Vp8StreamerType::Vp8StreamerType() : - LibavStreamerType("webm", "libvpx", "video/webm") -{ -} - -boost::shared_ptr Vp8StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr(new Vp8Streamer(request, connection, nh)); -} - -} diff --git a/web_video_server/src/vp9_streamer.cpp b/web_video_server/src/vp9_streamer.cpp deleted file mode 100644 index 8fcefd8..0000000 --- a/web_video_server/src/vp9_streamer.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include "web_video_server/vp9_streamer.h" - -namespace web_video_server -{ - -Vp9Streamer::Vp9Streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) : - LibavStreamer(request, connection, nh, "webm", "libvpx-vp9", "video/webm") -{ -} -Vp9Streamer::~Vp9Streamer() -{ -} - -void Vp9Streamer::initializeEncoder() -{ - - // codec options set up to provide somehow reasonable performance in cost of poor quality - // should be updated as soon as VP9 encoding matures - av_opt_set_int(codec_context_->priv_data, "pass", 1, 0); - av_opt_set_int(codec_context_->priv_data, "speed", 8, 0); - av_opt_set_int(codec_context_->priv_data, "cpu-used", 4, 0); // 8 is max - av_opt_set_int(codec_context_->priv_data, "crf", 20, 0); // 0..63 (higher is lower quality) -} - -Vp9StreamerType::Vp9StreamerType() : - LibavStreamerType("webm", "libvpx-vp9", "video/webm") -{ -} - -boost::shared_ptr Vp9StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, - async_web_server_cpp::HttpConnectionPtr connection, - rclcpp::Node::SharedPtr nh) -{ - return boost::shared_ptr(new Vp9Streamer(request, connection, nh)); -} - -} diff --git a/web_video_server/src/web_video_server.cpp b/web_video_server/src/web_video_server.cpp deleted file mode 100644 index c0eebf2..0000000 --- a/web_video_server/src/web_video_server.cpp +++ /dev/null @@ -1,389 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include "web_video_server/web_video_server.h" -#include "web_video_server/ros_compressed_streamer.h" -#include "web_video_server/jpeg_streamers.h" -#include "web_video_server/png_streamers.h" -#include "web_video_server/vp8_streamer.h" -#include "web_video_server/h264_streamer.h" -#include "web_video_server/vp9_streamer.h" -#include "async_web_server_cpp/http_reply.hpp" - -using namespace std::chrono_literals; -using namespace boost::placeholders; - -namespace web_video_server -{ - -static bool __verbose; - -static std::string __default_stream_type; - -static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward, - const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, - const char* end) -{ - if (__verbose) - { - // TODO reenable - // RCLCPP_INFO(nh->get_logger(), "Handling Request: %s", request.uri.c_str()); - } - try - { - forward(request, connection, begin, end); - return true; - } - catch (std::exception &e) - { - // TODO reenable - // RCLCPP_WARN(nh->get_logger(), "Error Handling Request: %s", e.what()); - return false; - } - return false; -} - -WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr &nh, rclcpp::Node::SharedPtr &private_nh) : - nh_(nh), handler_group_( - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)) -{ - rclcpp::Parameter parameter; - if (private_nh->get_parameter("port", parameter)) { - port_ = parameter.as_int(); - } else { - port_ = 8080; - } - if (private_nh->get_parameter("verbose", parameter)) { - __verbose = parameter.as_bool(); - } else { - __verbose = true; - } - - if (private_nh->get_parameter("address", parameter)) { - address_ = parameter.as_string(); - } else { - address_ = "0.0.0.0"; - } - - int server_threads; - if (private_nh->get_parameter("server_threads", parameter)) { - server_threads = parameter.as_int(); - } else { - server_threads = 1; - } - - if (private_nh->get_parameter("ros_threads", parameter)) { - ros_threads_ = parameter.as_int(); - } else { - ros_threads_ = 2; - } - if (private_nh->get_parameter("publish_rate", parameter)) { - publish_rate_ = parameter.as_double(); - } else { - publish_rate_ = -1.0; - } - - if (private_nh->get_parameter("default_stream_type", parameter)) { - __default_stream_type = parameter.as_string(); - } else { - __default_stream_type = "mjpeg"; - } - - stream_types_["mjpeg"] = boost::shared_ptr(new MjpegStreamerType()); - stream_types_["png"] = boost::shared_ptr(new PngStreamerType()); - stream_types_["ros_compressed"] = boost::shared_ptr(new RosCompressedStreamerType()); - stream_types_["vp8"] = boost::shared_ptr(new Vp8StreamerType()); - stream_types_["h264"] = boost::shared_ptr(new H264StreamerType()); - stream_types_["vp9"] = boost::shared_ptr(new Vp9StreamerType()); - - handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4)); - handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4)); - handler_group_.addHandlerForPath("/stream_viewer", - boost::bind(&WebVideoServer::handle_stream_viewer, this, _1, _2, _3, _4)); - handler_group_.addHandlerForPath("/snapshot", boost::bind(&WebVideoServer::handle_snapshot, this, _1, _2, _3, _4)); - - try - { - server_.reset( - new async_web_server_cpp::HttpServer(address_, boost::lexical_cast(port_), - boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4), - server_threads)); - } - catch(boost::exception& e) - { - RCLCPP_ERROR(nh_->get_logger(), "Exception when creating the web server! %s:%d", address_.c_str(), port_); - throw; - } -} - -WebVideoServer::~WebVideoServer() -{ -} - -void WebVideoServer::setup_cleanup_inactive_streams() -{ - std::function callback = std::bind(&WebVideoServer::cleanup_inactive_streams, this); - cleanup_timer_ = nh_->create_wall_timer(500ms, callback); -} - -void WebVideoServer::spin() -{ - server_->run(); - RCLCPP_INFO(nh_->get_logger(), "Waiting For connections on %s:%d", address_.c_str(), port_); - rclcpp::executors::MultiThreadedExecutor spinner(rclcpp::ExecutorOptions(), ros_threads_); - spinner.add_node(nh_); - if ( publish_rate_ > 0 ) { - nh_->create_wall_timer(1s / publish_rate_, [this](){restreamFrames(1.0 / publish_rate_);}); - } - spinner.spin(); - server_->stop(); -} - -void WebVideoServer::restreamFrames( double max_age ) -{ - boost::mutex::scoped_lock lock(subscriber_mutex_); - - typedef std::vector >::iterator itr_type; - - for (itr_type itr = image_subscribers_.begin(); itr < image_subscribers_.end(); ++itr) - { - (*itr)->restreamFrame( max_age ); - } -} - -void WebVideoServer::cleanup_inactive_streams() -{ - boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock); - if (lock) - { - typedef std::vector >::iterator itr_type; - itr_type new_end = std::partition(image_subscribers_.begin(), image_subscribers_.end(), - !boost::bind(&ImageStreamer::isInactive, _1)); - if (__verbose) - { - for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr) - { - RCLCPP_INFO(nh_->get_logger(), "Removed Stream: %s", (*itr)->getTopic().c_str()); - } - } - image_subscribers_.erase(new_end, image_subscribers_.end()); - } -} - -bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, - const char* end) -{ - std::string type = request.get_query_param_value_or_default("type", __default_stream_type); - if (stream_types_.find(type) != stream_types_.end()) - { - std::string topic = request.get_query_param_value_or_default("topic", ""); - // Fallback for topics without corresponding compressed topics - if (type == std::string("ros_compressed")) - { - std::string compressed_topic_name = topic + "/compressed"; - auto tnat = nh_->get_topic_names_and_types(); - bool did_find_compressed_topic = false; - for (auto topic_and_types : tnat) { - if (topic_and_types.second.size() > 1) { - // explicitly avoid topics with more than one type - break; - } - auto & topic_name = topic_and_types.first; - if(topic_name == compressed_topic_name || (topic_name.find("/") == 0 && topic_name.substr(1) == compressed_topic_name)){ - did_find_compressed_topic = true; - break; - } - } - if (!did_find_compressed_topic) - { - RCLCPP_WARN(nh_->get_logger(), "Could not find compressed image topic for %s, falling back to mjpeg", topic.c_str()); - type = "mjpeg"; - } - } - boost::shared_ptr streamer = stream_types_[type]->create_streamer(request, connection, nh_); - streamer->start(); - boost::mutex::scoped_lock lock(subscriber_mutex_); - image_subscribers_.push_back(streamer); - } - else - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin, - end); - } - return true; -} - -bool WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, - const char* end) -{ - boost::shared_ptr streamer(new JpegSnapshotStreamer(request, connection, nh_)); - streamer->start(); - - boost::mutex::scoped_lock lock(subscriber_mutex_); - image_subscribers_.push_back(streamer); - return true; -} - -bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, - const char* end) -{ - std::string type = request.get_query_param_value_or_default("type", __default_stream_type); - if (stream_types_.find(type) != stream_types_.end()) - { - std::string topic = request.get_query_param_value_or_default("topic", ""); - // Fallback for topics without corresponding compressed topics - if (type == std::string("ros_compressed")) - { - - std::string compressed_topic_name = topic + "/compressed"; - auto tnat = nh_->get_topic_names_and_types(); - bool did_find_compressed_topic = false; - for (auto topic_and_types : tnat) { - if (topic_and_types.second.size() > 1) { - // explicitly avoid topics with more than one type - break; - } - auto & topic_name = topic_and_types.first; - if(topic_name == compressed_topic_name || (topic_name.find("/") == 0 && topic_name.substr(1) == compressed_topic_name)){ - did_find_compressed_topic = true; - break; - } - } - if (!did_find_compressed_topic) - { - RCLCPP_WARN(nh_->get_logger(), "Could not find compressed image topic for %s, falling back to mjpeg", topic.c_str()); - type = "mjpeg"; - } - } - - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Content-type", "text/html;").write(connection); - - std::stringstream ss; - ss << "" << topic << ""; - ss << "

" << topic << "

"; - ss << stream_types_[type]->create_viewer(request); - ss << ""; - connection->write(ss.str()); - } - else - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin, - end); - } - return true; -} - -bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest &request, - async_web_server_cpp::HttpConnectionPtr connection, const char* begin, - const char* end) -{ - std::vector image_topics; - std::vector camera_info_topics; - auto tnat = nh_->get_topic_names_and_types(); - for (auto topic_and_types : tnat) { - if (topic_and_types.second.size() > 1) { - // explicitly avoid topics with more than one type - break; - } - auto & topic_name = topic_and_types.first; - auto & topic_type = topic_and_types.second[0]; // explicitly take the first - // TODO debugging - fprintf(stderr, "topic_type: %s\n", topic_type.c_str()); - if (topic_type == "sensor_msgs/msg/Image") - { - image_topics.push_back(topic_name); - } - else if (topic_type == "sensor_msgs/msg/CameraInfo") - { - camera_info_topics.push_back(topic_name); - } - } - - async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( - "Server", "web_video_server").header("Cache-Control", - "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header( - "Pragma", "no-cache").header("Content-type", "text/html;").write(connection); - - connection->write("" - "ROS Image Topic List" - "

Available ROS Image Topics:

"); - connection->write(""); - // Add the rest of the image topics that don't have camera_info. - connection->write(""); - return true; -} - -} - -int main(int argc, char **argv) -{ - rclcpp::init(argc, argv); - auto nh = std::make_shared("web_video_server"); - auto private_nh = std::make_shared("_web_video_server"); - - web_video_server::WebVideoServer server(nh, private_nh); - server.setup_cleanup_inactive_streams(); - server.spin(); - - return (0); -}