From 9cbb73fef1deb2d91597534fb19b1a0e0afd0710 Mon Sep 17 00:00:00 2001 From: Arthur Date: Tue, 25 Oct 2022 08:52:40 -0700 Subject: [PATCH 01/33] Initial commit --- .../config/encoder_parameters.yaml | 24 +++++++++---------- src/wr_control_drive_arm/launch/std.launch | 1 + src/wr_control_drive_arm/src/ArmMotor.cpp | 15 +++++++++--- .../launch/test/mock_arm.launch | 2 +- .../src/ArmTeleopLogic.cpp | 4 ++-- test_arm_control_stack.sh | 4 ++-- 6 files changed, 30 insertions(+), 20 deletions(-) diff --git a/src/wr_control_drive_arm/config/encoder_parameters.yaml b/src/wr_control_drive_arm/config/encoder_parameters.yaml index 1fce6c2e..9c654b5f 100644 --- a/src/wr_control_drive_arm/config/encoder_parameters.yaml +++ b/src/wr_control_drive_arm/config/encoder_parameters.yaml @@ -1,19 +1,19 @@ encoder_parameters: # elbow - - counts_per_rotation: -2048 - offset: 610 + - counts_per_rotation: 1000 #-2048 + offset: 0 #610 # forearm_roll - - counts_per_rotation: -2048 - offset: 540 + - counts_per_rotation: 1000 #-2048 + offset: 0 #540 # shoulder - - counts_per_rotation: -6144 - offset: 1129 + - counts_per_rotation: 1000 #-6144 + offset: 0 #1129 # turntable - - counts_per_rotation: 2048 - offset: 985 + - counts_per_rotation: 1000 #2048 + offset: 0 #985 # wrist_pitch - - counts_per_rotation: 2048 - offset: 886 + - counts_per_rotation: 1000 #2048 + offset: 0 #886 # wrist_roll - - counts_per_rotation: 2048 - offset: 1050 + - counts_per_rotation: 1000 #2048 + offset: 0 #1050 diff --git a/src/wr_control_drive_arm/launch/std.launch b/src/wr_control_drive_arm/launch/std.launch index 12c7e1a3..fd49e319 100644 --- a/src/wr_control_drive_arm/launch/std.launch +++ b/src/wr_control_drive_arm/launch/std.launch @@ -3,6 +3,7 @@ + diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp index 60220e71..a2a6b9a4 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ b/src/wr_control_drive_arm/src/ArmMotor.cpp @@ -5,6 +5,8 @@ * @date 2021-04-05 */ #include "ArmMotor.hpp" +#include +#include #include #include @@ -20,11 +22,13 @@ auto ArmMotor::corrMod(double i, double j) -> double { /// Currently consistent with the rad->enc equation as specified here. auto ArmMotor::radToEnc(double rads) const -> uint32_t{ - return this->COUNTS_PER_ROTATION * ArmMotor::corrMod(rads, 2 * M_PI)/(2 * M_PI) + this->ENCODER_OFFSET; + double remappedEnc = ArmMotor::corrMod(rads, 2 * M_PI)/(2 * M_PI); + return ArmMotor::corrMod((this->COUNTS_PER_ROTATION * remappedEnc) + this->ENCODER_OFFSET, this->COUNTS_PER_ROTATION); } auto ArmMotor::encToRad(uint32_t enc) const -> double{ - return ArmMotor::corrMod(static_cast(enc - this->ENCODER_OFFSET) / static_cast(this->COUNTS_PER_ROTATION) * 2 * M_PI + M_PI, 2 * M_PI) - M_PI; + double remappedEnc = ArmMotor::corrMod(static_cast(enc - this->ENCODER_OFFSET), static_cast(this->COUNTS_PER_ROTATION)) / this->COUNTS_PER_ROTATION; + return ArmMotor::corrMod( remappedEnc * 2 * M_PI + M_PI, 2 * M_PI) - M_PI; } /// Currently consistent with the enc->rad equation as specified here. @@ -52,16 +56,19 @@ void ArmMotor::storeEncoderVals(const Std_UInt32 &msg){ void ArmMotor::redirectPowerOutput(const Std_Float64 &msg){ // Set the speed to be the contained data + if(abs(msg->data) > 1) std::cout << "Received power " << msg->data << " from PID for motor " << motorName << std::endl; if(this->getMotorState() == MotorState::RUN_TO_TARGET) this->setPower(static_cast(msg->data) * this->maxPower, MotorState::RUN_TO_TARGET); } void ArmMotor::storeStallStatus(const Std_Bool &msg) { if (static_cast(msg->data)) { if ((ros::Time::now() - beginStallTime).toSec() >= STALL_THRESHOLD_TIME) { + std::cout << "over lim" << std::endl; this->setPower(0.0F, MotorState::STALLING); } } else { beginStallTime = ros::Time::now(); + //std::cout << "below lim" << std::endl; } } @@ -114,6 +121,7 @@ void ArmMotor::runToTarget(uint32_t targetCounts, float power){ } auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool{ + std::cout << "TOLERANCE: " << tolerance << std::endl; // Compute the upper and lower bounds in the finite encoder space uint32_t lBound = ArmMotor::corrMod(static_cast(targetCounts - tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); uint32_t uBound = ArmMotor::corrMod(static_cast(targetCounts + tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); @@ -126,7 +134,8 @@ auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const /// Current tolerance is ±0.1 degree w.r.t. the current number of counts per rotation auto ArmMotor::hasReachedTarget(uint32_t targetCounts) const -> bool{ - return ArmMotor::hasReachedTarget(targetCounts, ArmMotor::TOLERANCE_RATIO * static_cast(std::abs(this->COUNTS_PER_ROTATION))); + auto tol = ArmMotor::TOLERANCE_RATIO * static_cast(std::abs(this->COUNTS_PER_ROTATION)); + return ArmMotor::hasReachedTarget(targetCounts, std::max(1.0,tol)); } auto ArmMotor::getMotorState() const -> MotorState{ diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index 23eed457..f49a1838 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -2,7 +2,7 @@ - + diff --git a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp index 52bfbb9e..f50afeb6 100644 --- a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp +++ b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp @@ -50,8 +50,8 @@ auto main(int argc, char** argv) -> int{ constexpr float STEP_Y = 0.003; constexpr float STEP_Z = 0.003; - constexpr float HOME_X = -0.7; - constexpr float HOME_Y = 0.0; + constexpr float HOME_X = 0.0; + constexpr float HOME_Y = -0.7; constexpr float HOME_Z = 0.2; diff --git a/test_arm_control_stack.sh b/test_arm_control_stack.sh index d86b8bb0..68a16dd2 100755 --- a/test_arm_control_stack.sh +++ b/test_arm_control_stack.sh @@ -1,7 +1,7 @@ #!/bin/bash ROOT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" cd $ROOT_DIR -./assemble.py build +./assemble.py build -o #gnome-terminal -- roscore #rostopic list &>./out.temp; #COUNT=$(grep -Ec "Unable to communicate with master" out.temp) @@ -11,6 +11,6 @@ cd $ROOT_DIR #done #rm ./out.temp; export WROVER_LOCAL=true -export WROVER_HW=REAL +export WROVER_HW=MOCK roslaunch wr_entry_point mock_arm.launch From 633d124fa6f0de2e4b47336fe156f65cc98bb478 Mon Sep 17 00:00:00 2001 From: Ben Nowotny Date: Wed, 26 Oct 2022 00:53:31 -0500 Subject: [PATCH 02/33] fixin' things --- .../config/encoder_parameters.yaml | 12 +++++----- .../src/ArmControlSystem.cpp | 2 +- src/wr_control_drive_arm/src/ArmMotor.cpp | 22 +++++++++++-------- src/wroboarm_22/config/joint_limits.yaml | 12 +++++----- src/wroboarm_22/urdf/wroboarm_22.urdf | 12 +++++----- test_arm_control_stack.sh | 2 ++ 6 files changed, 34 insertions(+), 28 deletions(-) diff --git a/src/wr_control_drive_arm/config/encoder_parameters.yaml b/src/wr_control_drive_arm/config/encoder_parameters.yaml index 9c654b5f..447ef233 100644 --- a/src/wr_control_drive_arm/config/encoder_parameters.yaml +++ b/src/wr_control_drive_arm/config/encoder_parameters.yaml @@ -1,19 +1,19 @@ encoder_parameters: # elbow - counts_per_rotation: 1000 #-2048 - offset: 0 #610 + offset: 500 #610 # forearm_roll - counts_per_rotation: 1000 #-2048 - offset: 0 #540 + offset: 500 #540 # shoulder - counts_per_rotation: 1000 #-6144 - offset: 0 #1129 + offset: 500 #1129 # turntable - counts_per_rotation: 1000 #2048 - offset: 0 #985 + offset: 500 #985 # wrist_pitch - counts_per_rotation: 1000 #2048 - offset: 0 #886 + offset: 500 #886 # wrist_roll - counts_per_rotation: 1000 #2048 - offset: 0 #1050 + offset: 500 #1050 diff --git a/src/wr_control_drive_arm/src/ArmControlSystem.cpp b/src/wr_control_drive_arm/src/ArmControlSystem.cpp index 2dc5dbf9..cd95b79c 100644 --- a/src/wr_control_drive_arm/src/ArmControlSystem.cpp +++ b/src/wr_control_drive_arm/src/ArmControlSystem.cpp @@ -129,7 +129,7 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server // For each joint specified in the currTargetPosition... for(const auto &joint : joints){ - // joint->exectute(); + joint->exectute(); for(int k = 0; k < joint->getDegreesOfFreedom(); k++){ diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp index a2a6b9a4..ce8610dc 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ b/src/wr_control_drive_arm/src/ArmMotor.cpp @@ -23,11 +23,11 @@ auto ArmMotor::corrMod(double i, double j) -> double { /// Currently consistent with the rad->enc equation as specified here. auto ArmMotor::radToEnc(double rads) const -> uint32_t{ double remappedEnc = ArmMotor::corrMod(rads, 2 * M_PI)/(2 * M_PI); - return ArmMotor::corrMod((this->COUNTS_PER_ROTATION * remappedEnc) + this->ENCODER_OFFSET, this->COUNTS_PER_ROTATION); + return ArmMotor::corrMod((this->COUNTS_PER_ROTATION * remappedEnc) + this->ENCODER_OFFSET, abs(this->COUNTS_PER_ROTATION)); } auto ArmMotor::encToRad(uint32_t enc) const -> double{ - double remappedEnc = ArmMotor::corrMod(static_cast(enc - this->ENCODER_OFFSET), static_cast(this->COUNTS_PER_ROTATION)) / this->COUNTS_PER_ROTATION; + double remappedEnc = ArmMotor::corrMod(static_cast(enc - this->ENCODER_OFFSET), abs(static_cast(this->COUNTS_PER_ROTATION))) / this->COUNTS_PER_ROTATION; return ArmMotor::corrMod( remappedEnc * 2 * M_PI + M_PI, 2 * M_PI) - M_PI; } @@ -46,7 +46,7 @@ void ArmMotor::storeEncoderVals(const Std_UInt32 &msg){ this->feedbackPub.publish(feedbackMsg); if(this->currState == MotorState::RUN_TO_TARGET){ - std::cout << "[2] " << (hasReachedTarget(this->target) ? "at target " : "not at target ") << this->target << ":" << this->encoderVal << std::endl; + std::cout << "[2] motor " << motorName << " position " << (hasReachedTarget(this->target) ? "at target " : "not at target ") << this->target << ":" << this->encoderVal << std::endl; if(hasReachedTarget(this->target)){ std::cout << "[1] stop motor" << std::endl; this->setPower(0.F, MotorState::STOP); @@ -123,13 +123,17 @@ void ArmMotor::runToTarget(uint32_t targetCounts, float power){ auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool{ std::cout << "TOLERANCE: " << tolerance << std::endl; // Compute the upper and lower bounds in the finite encoder space - uint32_t lBound = ArmMotor::corrMod(static_cast(targetCounts - tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); - uint32_t uBound = ArmMotor::corrMod(static_cast(targetCounts + tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); + int32_t lBound = ArmMotor::corrMod(static_cast(targetCounts - tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); + int32_t uBound = ArmMotor::corrMod(static_cast(targetCounts + tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); + std::cout << "LBOUND: " << (lBound) << " UBOUND: " << (uBound) << std::endl; + auto position = ArmMotor::corrMod(getEncoderCounts(), ENCODER_BOUNDS[1]); + std::cout << "POSITION RAW: " << encToRad(getEncoderCounts()) << "/" << getEncoderCounts() << std::endl; + std::cout << "POSITION: " << encToRad(position) << "/" << position << std::endl; // If the computed lower bound is lower than the upper bound, perform the computation normally if(lBound < uBound) - return this->getEncoderCounts() <= uBound && this->getEncoderCounts() >=lBound; + return position <= uBound && position >=lBound; // Otherwise, check if the value is outside either bound and negate the response - return this->getEncoderCounts() <= uBound || this->getEncoderCounts() >= lBound; + return position <= uBound || position >= lBound; } /// Current tolerance is ±0.1 degree w.r.t. the current number of counts per rotation @@ -161,7 +165,7 @@ void ArmMotor::setPower(float power, MotorState state){ void ArmMotor::runToTarget(uint32_t targetCounts, float power, bool block){ this->target = targetCounts; - this->maxPower = power; + this->maxPower = abs(power); // If we are not at our target... if(!this->hasReachedTarget(targetCounts)){ // std::cout << "has not reached target" << std::endl; @@ -173,7 +177,7 @@ void ArmMotor::runToTarget(uint32_t targetCounts, float power, bool block){ // long int direction = targetCounts - this->getEncoderCounts(); // power = abs(power) * (corrMod(direction, ((long int)this->COUNTS_PER_ROTATION)) < corrMod(-direction, ((long int)this->COUNTS_PER_ROTATION)) ? 1 : -1); - this->setPower(power, MotorState::RUN_TO_TARGET); + // this->setPower(power, MotorState::RUN_TO_TARGET); // Otherwise, stop the motor } else { diff --git a/src/wroboarm_22/config/joint_limits.yaml b/src/wroboarm_22/config/joint_limits.yaml index b9def49a..cd2117cd 100644 --- a/src/wroboarm_22/config/joint_limits.yaml +++ b/src/wroboarm_22/config/joint_limits.yaml @@ -9,8 +9,8 @@ default_acceleration_scaling_factor: 1.0 # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] joint_limits: elbow: - max_position: 0.436 - min_position: -2.5307 + max_position: 1.57 + min_position: -1.57 has_velocity_limits: false max_velocity: 0 has_acceleration_limits: false @@ -23,15 +23,15 @@ joint_limits: has_acceleration_limits: false max_acceleration: 0 shoulder: - max_position: 2.2689 - min_position: -0.87266 + max_position: 1.57 + min_position: -1.57 has_velocity_limits: false max_velocity: 0 has_acceleration_limits: false max_acceleration: 0 turntable: - max_position: 3.1 - min_position: -3.1 + max_position: 1.57 + min_position: -1.57 has_velocity_limits: false max_velocity: 0 has_acceleration_limits: false diff --git a/src/wroboarm_22/urdf/wroboarm_22.urdf b/src/wroboarm_22/urdf/wroboarm_22.urdf index 22dda5d9..79bbe3ca 100644 --- a/src/wroboarm_22/urdf/wroboarm_22.urdf +++ b/src/wroboarm_22/urdf/wroboarm_22.urdf @@ -49,7 +49,7 @@ - + @@ -81,7 +81,7 @@ - + @@ -113,7 +113,7 @@ - + @@ -145,7 +145,7 @@ - + @@ -177,7 +177,7 @@ - + @@ -209,7 +209,7 @@ - + diff --git a/test_arm_control_stack.sh b/test_arm_control_stack.sh index 68a16dd2..1a3ea3f6 100755 --- a/test_arm_control_stack.sh +++ b/test_arm_control_stack.sh @@ -12,5 +12,7 @@ cd $ROOT_DIR #rm ./out.temp; export WROVER_LOCAL=true export WROVER_HW=MOCK +MOTOR_TO_INSPECT=11 +(sleep 2 && rqt_plot /control/arm/$MOTOR_TO_INSPECT/output /control/arm/$MOTOR_TO_INSPECT/setpoint /control/arm/$MOTOR_TO_INSPECT/feedback) & #/hsi/roboclaw/aux1/cmd/left roslaunch wr_entry_point mock_arm.launch From dc87bfc4b7c9803b2301e0212751fb750cbb16c1 Mon Sep 17 00:00:00 2001 From: Arthur Date: Wed, 26 Oct 2022 17:53:30 -0700 Subject: [PATCH 03/33] Undid local testing changes --- src/wr_control_drive_arm/launch/std.launch | 1 - src/wr_entry_point/launch/test/mock_arm.launch | 2 +- test_arm_control_stack.sh | 4 ++-- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/wr_control_drive_arm/launch/std.launch b/src/wr_control_drive_arm/launch/std.launch index fd49e319..12c7e1a3 100644 --- a/src/wr_control_drive_arm/launch/std.launch +++ b/src/wr_control_drive_arm/launch/std.launch @@ -3,7 +3,6 @@ - diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index f49a1838..23eed457 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -2,7 +2,7 @@ - + diff --git a/test_arm_control_stack.sh b/test_arm_control_stack.sh index 1a3ea3f6..3ebbc39f 100755 --- a/test_arm_control_stack.sh +++ b/test_arm_control_stack.sh @@ -1,7 +1,7 @@ #!/bin/bash ROOT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" cd $ROOT_DIR -./assemble.py build -o +./assemble.py build #gnome-terminal -- roscore #rostopic list &>./out.temp; #COUNT=$(grep -Ec "Unable to communicate with master" out.temp) @@ -11,7 +11,7 @@ cd $ROOT_DIR #done #rm ./out.temp; export WROVER_LOCAL=true -export WROVER_HW=MOCK +export WROVER_HW=REAL MOTOR_TO_INSPECT=11 (sleep 2 && rqt_plot /control/arm/$MOTOR_TO_INSPECT/output /control/arm/$MOTOR_TO_INSPECT/setpoint /control/arm/$MOTOR_TO_INSPECT/feedback) & #/hsi/roboclaw/aux1/cmd/left roslaunch wr_entry_point mock_arm.launch From 872b85a939b72e64c301af0fed64c476fa7ea9b4 Mon Sep 17 00:00:00 2001 From: Arthur Date: Wed, 26 Oct 2022 17:55:10 -0700 Subject: [PATCH 04/33] Undid local testing changes 2: electric boogaloo --- .../config/encoder_parameters.yaml | 24 +++++++++---------- 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/src/wr_control_drive_arm/config/encoder_parameters.yaml b/src/wr_control_drive_arm/config/encoder_parameters.yaml index 447ef233..1fce6c2e 100644 --- a/src/wr_control_drive_arm/config/encoder_parameters.yaml +++ b/src/wr_control_drive_arm/config/encoder_parameters.yaml @@ -1,19 +1,19 @@ encoder_parameters: # elbow - - counts_per_rotation: 1000 #-2048 - offset: 500 #610 + - counts_per_rotation: -2048 + offset: 610 # forearm_roll - - counts_per_rotation: 1000 #-2048 - offset: 500 #540 + - counts_per_rotation: -2048 + offset: 540 # shoulder - - counts_per_rotation: 1000 #-6144 - offset: 500 #1129 + - counts_per_rotation: -6144 + offset: 1129 # turntable - - counts_per_rotation: 1000 #2048 - offset: 500 #985 + - counts_per_rotation: 2048 + offset: 985 # wrist_pitch - - counts_per_rotation: 1000 #2048 - offset: 500 #886 + - counts_per_rotation: 2048 + offset: 886 # wrist_roll - - counts_per_rotation: 1000 #2048 - offset: 500 #1050 + - counts_per_rotation: 2048 + offset: 1050 From 6498a693fe715d0497cba1b1c383ba22c62c6aed Mon Sep 17 00:00:00 2001 From: Arthur Date: Thu, 27 Oct 2022 17:32:19 -0700 Subject: [PATCH 05/33] more fixin' --- .../src/ArmControlSystem.cpp | 16 ++++++++++++++-- src/wr_control_drive_arm/src/ArmMotor.cpp | 1 - src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp | 3 ++- 3 files changed, 16 insertions(+), 4 deletions(-) diff --git a/src/wr_control_drive_arm/src/ArmControlSystem.cpp b/src/wr_control_drive_arm/src/ArmControlSystem.cpp index cd95b79c..8da28047 100644 --- a/src/wr_control_drive_arm/src/ArmControlSystem.cpp +++ b/src/wr_control_drive_arm/src/ArmControlSystem.cpp @@ -129,11 +129,21 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server // For each joint specified in the currTargetPosition... for(const auto &joint : joints){ - joint->exectute(); - for(int k = 0; k < joint->getDegreesOfFreedom(); k++){ + if (joint->getMotor(k)->getMotorState() == MotorState::MOVING) { + std::cout << "Moving" << std::endl; + } else if (joint->getMotor(k)->getMotorState() == MotorState::RUN_TO_TARGET) { + std::cout << "Run to target" << std::endl; + } else if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { + std::cout << "Stalling" << std::endl; + } else if (joint->getMotor(k)->getMotorState() == MotorState::STOP) { + std::cout << "Stop" << std::endl; + } else { + std::cout << "Error" << std::endl; + } if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { + std::cout << "ACS stall detected" << std::endl; IKEnabled = false; std_srvs::Trigger srv; if (enableServiceClient.call(srv)) { @@ -148,6 +158,8 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server // std::cout<getEncoderCounts()<exectute(); + // if (!joint->exectute()) { // IKEnabled = false; // std_srvs::Trigger srv; diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp index ce8610dc..c0e2fc6d 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ b/src/wr_control_drive_arm/src/ArmMotor.cpp @@ -68,7 +68,6 @@ void ArmMotor::storeStallStatus(const Std_Bool &msg) { } } else { beginStallTime = ros::Time::now(); - //std::cout << "below lim" << std::endl; } } diff --git a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp index f50afeb6..4793cbe2 100644 --- a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp +++ b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp @@ -10,6 +10,7 @@ #include "tf2/LinearMath/Vector3.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.h" #include +#include #include #include #include @@ -62,7 +63,7 @@ auto main(int argc, char** argv) -> int{ float y_pos = HOME_Y; float z_pos = HOME_Z; - tf2::Quaternion orientation {0, sin(-M_PI/4), 0, cos(-M_PI/4)}; + tf2::Quaternion orientation {sin(M_PI/4), 0, 0, cos(-M_PI/4)}; orientation = orientation; const tf2::Quaternion SPIN_X {sin(2*M_PI/1000), 0, 0, cos(2*M_PI/1000)}; From b11e4e1b3dd5ea340f16a786c680061030637d3a Mon Sep 17 00:00:00 2001 From: WRover Date: Thu, 27 Oct 2022 20:03:54 -0500 Subject: [PATCH 06/33] Fixing PID constants --- .../config/arm_motor_PID.yaml | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/wr_control_drive_arm/config/arm_motor_PID.yaml b/src/wr_control_drive_arm/config/arm_motor_PID.yaml index 2ac19e48..33ec8ae2 100644 --- a/src/wr_control_drive_arm/config/arm_motor_PID.yaml +++ b/src/wr_control_drive_arm/config/arm_motor_PID.yaml @@ -3,7 +3,7 @@ controllers: - setpointTopic: "/control/arm/00/setpoint" feedbackTopic: "/control/arm/00/feedback" outputTopic: "/control/arm/00/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 @@ -12,7 +12,7 @@ controllers: - setpointTopic: "/control/arm/01/setpoint" feedbackTopic: "/control/arm/01/feedback" outputTopic: "/control/arm/01/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 @@ -21,7 +21,7 @@ controllers: - setpointTopic: "/control/arm/10/setpoint" feedbackTopic: "/control/arm/10/feedback" outputTopic: "/control/arm/10/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 @@ -30,7 +30,7 @@ controllers: - setpointTopic: "/control/arm/11/setpoint" feedbackTopic: "/control/arm/11/feedback" outputTopic: "/control/arm/11/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 @@ -39,7 +39,7 @@ controllers: - setpointTopic: "/control/arm/20/setpoint" feedbackTopic: "/control/arm/20/feedback" outputTopic: "/control/arm/20/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 @@ -48,7 +48,7 @@ controllers: - setpointTopic: "/control/arm/21/setpoint" feedbackTopic: "/control/arm/21/feedback" outputTopic: "/control/arm/21/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 @@ -57,8 +57,8 @@ controllers: - setpointTopic: "/control/arm/3000/setpoint" feedbackTopic: "/control/arm/3000/feedback" outputTopic: "/control/arm/3000/output" - P: 3000 + P: 5 I: 0 D: 0 min: -1 - max: 1 \ No newline at end of file + max: 1 From 5f0ac8d54a48e87f63b5e89074db50baa2f4217a Mon Sep 17 00:00:00 2001 From: Arthur Date: Thu, 10 Nov 2022 16:27:59 -0800 Subject: [PATCH 07/33] Using WROVER_HW to set encoder params --- .../config/encoder_parameters_mock.yaml | 19 +++++++++++++++++++ ...ters.yaml => encoder_parameters_real.yaml} | 0 src/wr_control_drive_arm/launch/std.launch | 3 ++- .../launch/test/mock_arm.launch | 5 ----- 4 files changed, 21 insertions(+), 6 deletions(-) create mode 100644 src/wr_control_drive_arm/config/encoder_parameters_mock.yaml rename src/wr_control_drive_arm/config/{encoder_parameters.yaml => encoder_parameters_real.yaml} (100%) diff --git a/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml b/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml new file mode 100644 index 00000000..5c855815 --- /dev/null +++ b/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml @@ -0,0 +1,19 @@ +encoder_parameters: +# elbow + - counts_per_rotation: 1000 + offset: 500 +# forearm_roll + - counts_per_rotation: 1000 + offset: 500 +# shoulder + - counts_per_rotation: 1000 + offset: 500 +# turntable + - counts_per_rotation: 1000 + offset: 500 +# wrist_pitch + - counts_per_rotation: 1000 + offset: 500 +# wrist_roll + - counts_per_rotation: 1000 + offset: 500 diff --git a/src/wr_control_drive_arm/config/encoder_parameters.yaml b/src/wr_control_drive_arm/config/encoder_parameters_real.yaml similarity index 100% rename from src/wr_control_drive_arm/config/encoder_parameters.yaml rename to src/wr_control_drive_arm/config/encoder_parameters_real.yaml diff --git a/src/wr_control_drive_arm/launch/std.launch b/src/wr_control_drive_arm/launch/std.launch index 12c7e1a3..e9a2fb2f 100644 --- a/src/wr_control_drive_arm/launch/std.launch +++ b/src/wr_control_drive_arm/launch/std.launch @@ -4,7 +4,8 @@ - + + diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index 23eed457..ca039848 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -1,10 +1,5 @@ - - - - - From ede3d26021c13c19af38bfb8e64e9dd53986cfd3 Mon Sep 17 00:00:00 2001 From: Arthur Date: Mon, 14 Nov 2022 20:07:25 -0800 Subject: [PATCH 08/33] Updated moveit using new URDF --- src/wroboarm_23/.setup_assistant | 11 + src/wroboarm_23/CMakeLists.txt | 10 + src/wroboarm_23/config/cartesian_limits.yaml | 5 + src/wroboarm_23/config/chomp_planning.yaml | 18 + src/wroboarm_23/config/fake_controllers.yaml | 15 + .../config/gazebo_controllers.yaml | 4 + .../config/gazebo_wroboarm_23.urdf | 262 +++++++ src/wroboarm_23/config/joint_limits.yaml | 40 + .../joint_names_ArmAssembly.SLDASM.yaml | 1 + src/wroboarm_23/config/kinematics.yaml | 1 + src/wroboarm_23/config/ompl_planning.yaml | 157 ++++ src/wroboarm_23/config/ros_controllers.yaml | 40 + src/wroboarm_23/config/sensors_3d.yaml | 2 + .../config/simple_moveit_controllers.yaml | 12 + src/wroboarm_23/config/stomp_planning.yaml | 39 + src/wroboarm_23/config/wroboarm_23.srdf | 28 + src/wroboarm_23/export.log | 705 ++++++++++++++++++ .../launch/chomp_planning_pipeline.launch.xml | 24 + .../launch/default_warehouse_db.launch | 15 + src/wroboarm_23/launch/demo.launch | 69 ++ src/wroboarm_23/launch/demo_gazebo.launch | 21 + src/wroboarm_23/launch/display.launch | 20 + .../fake_moveit_controller_manager.launch.xml | 12 + src/wroboarm_23/launch/gazebo.launch | 32 + .../launch/joystick_control.launch | 17 + src/wroboarm_23/launch/move_group.launch | 105 +++ src/wroboarm_23/launch/moveit.rviz | 131 ++++ src/wroboarm_23/launch/moveit_rviz.launch | 15 + .../ompl-chomp_planning_pipeline.launch.xml | 20 + .../launch/ompl_planning_pipeline.launch.xml | 27 + ...otion_planner_planning_pipeline.launch.xml | 15 + .../launch/planning_context.launch | 26 + .../launch/planning_pipeline.launch.xml | 10 + ...ntrol_moveit_controller_manager.launch.xml | 4 + src/wroboarm_23/launch/ros_controllers.launch | 11 + .../launch/run_benchmark_ompl.launch | 21 + .../launch/sensor_manager.launch.xml | 17 + src/wroboarm_23/launch/setup_assistant.launch | 16 + ...imple_moveit_controller_manager.launch.xml | 8 + .../launch/stomp_planning_pipeline.launch.xml | 26 + .../launch/trajectory_execution.launch.xml | 23 + src/wroboarm_23/launch/warehouse.launch | 15 + .../launch/warehouse_settings.launch.xml | 16 + ...oboarm_23_moveit_sensor_manager.launch.xml | 3 + src/wroboarm_23/meshes/base_link.STL | Bin 0 -> 11984 bytes src/wroboarm_23/meshes/carpus_link.STL | Bin 0 -> 50884 bytes src/wroboarm_23/meshes/endEffector_link.STL | Bin 0 -> 54084 bytes src/wroboarm_23/meshes/forearm_link.STL | Bin 0 -> 19984 bytes src/wroboarm_23/meshes/turntable_link.STL | Bin 0 -> 53584 bytes src/wroboarm_23/meshes/upperArm_link.STL | Bin 0 -> 25984 bytes src/wroboarm_23/meshes/wrist_link.STL | Bin 0 -> 12484 bytes src/wroboarm_23/package.xml | 41 + src/wroboarm_23/urdf/ArmAssembly.SLDASM.csv | 8 + src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf | 365 +++++++++ 54 files changed, 2483 insertions(+) create mode 100644 src/wroboarm_23/.setup_assistant create mode 100644 src/wroboarm_23/CMakeLists.txt create mode 100644 src/wroboarm_23/config/cartesian_limits.yaml create mode 100644 src/wroboarm_23/config/chomp_planning.yaml create mode 100644 src/wroboarm_23/config/fake_controllers.yaml create mode 100644 src/wroboarm_23/config/gazebo_controllers.yaml create mode 100644 src/wroboarm_23/config/gazebo_wroboarm_23.urdf create mode 100644 src/wroboarm_23/config/joint_limits.yaml create mode 100644 src/wroboarm_23/config/joint_names_ArmAssembly.SLDASM.yaml create mode 100644 src/wroboarm_23/config/kinematics.yaml create mode 100644 src/wroboarm_23/config/ompl_planning.yaml create mode 100644 src/wroboarm_23/config/ros_controllers.yaml create mode 100644 src/wroboarm_23/config/sensors_3d.yaml create mode 100644 src/wroboarm_23/config/simple_moveit_controllers.yaml create mode 100644 src/wroboarm_23/config/stomp_planning.yaml create mode 100644 src/wroboarm_23/config/wroboarm_23.srdf create mode 100644 src/wroboarm_23/export.log create mode 100644 src/wroboarm_23/launch/chomp_planning_pipeline.launch.xml create mode 100644 src/wroboarm_23/launch/default_warehouse_db.launch create mode 100644 src/wroboarm_23/launch/demo.launch create mode 100644 src/wroboarm_23/launch/demo_gazebo.launch create mode 100644 src/wroboarm_23/launch/display.launch create mode 100644 src/wroboarm_23/launch/fake_moveit_controller_manager.launch.xml create mode 100644 src/wroboarm_23/launch/gazebo.launch create mode 100644 src/wroboarm_23/launch/joystick_control.launch create mode 100644 src/wroboarm_23/launch/move_group.launch create mode 100644 src/wroboarm_23/launch/moveit.rviz create mode 100644 src/wroboarm_23/launch/moveit_rviz.launch create mode 100644 src/wroboarm_23/launch/ompl-chomp_planning_pipeline.launch.xml create mode 100644 src/wroboarm_23/launch/ompl_planning_pipeline.launch.xml create mode 100644 src/wroboarm_23/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml create mode 100644 src/wroboarm_23/launch/planning_context.launch create mode 100644 src/wroboarm_23/launch/planning_pipeline.launch.xml create mode 100644 src/wroboarm_23/launch/ros_control_moveit_controller_manager.launch.xml create mode 100644 src/wroboarm_23/launch/ros_controllers.launch create mode 100644 src/wroboarm_23/launch/run_benchmark_ompl.launch create mode 100644 src/wroboarm_23/launch/sensor_manager.launch.xml create mode 100644 src/wroboarm_23/launch/setup_assistant.launch create mode 100644 src/wroboarm_23/launch/simple_moveit_controller_manager.launch.xml create mode 100644 src/wroboarm_23/launch/stomp_planning_pipeline.launch.xml create mode 100644 src/wroboarm_23/launch/trajectory_execution.launch.xml create mode 100644 src/wroboarm_23/launch/warehouse.launch create mode 100644 src/wroboarm_23/launch/warehouse_settings.launch.xml create mode 100644 src/wroboarm_23/launch/wroboarm_23_moveit_sensor_manager.launch.xml create mode 100644 src/wroboarm_23/meshes/base_link.STL create mode 100644 src/wroboarm_23/meshes/carpus_link.STL create mode 100644 src/wroboarm_23/meshes/endEffector_link.STL create mode 100644 src/wroboarm_23/meshes/forearm_link.STL create mode 100644 src/wroboarm_23/meshes/turntable_link.STL create mode 100644 src/wroboarm_23/meshes/upperArm_link.STL create mode 100644 src/wroboarm_23/meshes/wrist_link.STL create mode 100644 src/wroboarm_23/package.xml create mode 100644 src/wroboarm_23/urdf/ArmAssembly.SLDASM.csv create mode 100644 src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf diff --git a/src/wroboarm_23/.setup_assistant b/src/wroboarm_23/.setup_assistant new file mode 100644 index 00000000..d7285f38 --- /dev/null +++ b/src/wroboarm_23/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: wroboarm_23 + relative_path: urdf/ArmAssembly.SLDASM.urdf + xacro_args: "" + SRDF: + relative_path: config/wroboarm_23.srdf + CONFIG: + author_name: Ben Nowotny + author_email: bennowotny65535@gmail.com + generated_timestamp: 1668478000 \ No newline at end of file diff --git a/src/wroboarm_23/CMakeLists.txt b/src/wroboarm_23/CMakeLists.txt new file mode 100644 index 00000000..f1e67c4f --- /dev/null +++ b/src/wroboarm_23/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.1.3) +project(wroboarm_23) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/src/wroboarm_23/config/cartesian_limits.yaml b/src/wroboarm_23/config/cartesian_limits.yaml new file mode 100644 index 00000000..7df72f69 --- /dev/null +++ b/src/wroboarm_23/config/cartesian_limits.yaml @@ -0,0 +1,5 @@ +cartesian_limits: + max_trans_vel: 1 + max_trans_acc: 2.25 + max_trans_dec: -5 + max_rot_vel: 1.57 diff --git a/src/wroboarm_23/config/chomp_planning.yaml b/src/wroboarm_23/config/chomp_planning.yaml new file mode 100644 index 00000000..eb9c9122 --- /dev/null +++ b/src/wroboarm_23/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.0 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearance: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: false +max_recovery_attempts: 5 diff --git a/src/wroboarm_23/config/fake_controllers.yaml b/src/wroboarm_23/config/fake_controllers.yaml new file mode 100644 index 00000000..46de675b --- /dev/null +++ b/src/wroboarm_23/config/fake_controllers.yaml @@ -0,0 +1,15 @@ +controller_list: + - name: fake_arm_controller + type: $(arg fake_execution_type) + joints: + - turntable_joint + - shoulder_joint + - elbowPitch_joint + - elbowRoll_joint + - wristPitch_joint + - wristRoll_link +initial: # Define initial robot poses per group +# - group: arm +# pose: home + + [] \ No newline at end of file diff --git a/src/wroboarm_23/config/gazebo_controllers.yaml b/src/wroboarm_23/config/gazebo_controllers.yaml new file mode 100644 index 00000000..e4d2eb00 --- /dev/null +++ b/src/wroboarm_23/config/gazebo_controllers.yaml @@ -0,0 +1,4 @@ +# Publish joint_states +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 diff --git a/src/wroboarm_23/config/gazebo_wroboarm_23.urdf b/src/wroboarm_23/config/gazebo_wroboarm_23.urdf new file mode 100644 index 00000000..e4edc521 --- /dev/null +++ b/src/wroboarm_23/config/gazebo_wroboarm_23.urdf @@ -0,0 +1,262 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + / + + + + diff --git a/src/wroboarm_23/config/joint_limits.yaml b/src/wroboarm_23/config/joint_limits.yaml new file mode 100644 index 00000000..e565424c --- /dev/null +++ b/src/wroboarm_23/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: + elbowPitch_joint: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + elbowRoll_joint: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + shoulder_joint: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + turntable_joint: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + wristPitch_joint: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + wristRoll_link: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/src/wroboarm_23/config/joint_names_ArmAssembly.SLDASM.yaml b/src/wroboarm_23/config/joint_names_ArmAssembly.SLDASM.yaml new file mode 100644 index 00000000..05cd2083 --- /dev/null +++ b/src/wroboarm_23/config/joint_names_ArmAssembly.SLDASM.yaml @@ -0,0 +1 @@ +controller_joint_names: ['', 'turntable_joint', 'shoulder_joint', 'elbowPitch_joint', 'elbowRoll_joint', 'wristPitch_joint', 'wristRoll_link', ] diff --git a/src/wroboarm_23/config/kinematics.yaml b/src/wroboarm_23/config/kinematics.yaml new file mode 100644 index 00000000..9e26dfee --- /dev/null +++ b/src/wroboarm_23/config/kinematics.yaml @@ -0,0 +1 @@ +{} \ No newline at end of file diff --git a/src/wroboarm_23/config/ompl_planning.yaml b/src/wroboarm_23/config/ompl_planning.yaml new file mode 100644 index 00000000..5e0528df --- /dev/null +++ b/src/wroboarm_23/config/ompl_planning.yaml @@ -0,0 +1,157 @@ +planner_configs: + AnytimePathShortening: + type: geometric::AnytimePathShortening + shortcut: true # Attempt to shortcut all new solution paths + hybridize: true # Compute hybrid solution trajectories + max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + num_planners: 4 # The number of default planners to use for planning + planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +arm: + planner_configs: + - AnytimePathShortening + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints(turntable_joint,shoulder_joint) + longest_valid_segment_fraction: 0.005 diff --git a/src/wroboarm_23/config/ros_controllers.yaml b/src/wroboarm_23/config/ros_controllers.yaml new file mode 100644 index 00000000..537c68ae --- /dev/null +++ b/src/wroboarm_23/config/ros_controllers.yaml @@ -0,0 +1,40 @@ +arm_controller: + type: effort_controllers/JointTrajectoryController + joints: + - turntable_joint + - shoulder_joint + - elbowPitch_joint + - elbowRoll_joint + - wristPitch_joint + - wristRoll_link + gains: + turntable_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + shoulder_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + elbowPitch_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + elbowRoll_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + wristPitch_joint: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + wristRoll_link: + p: 100 + d: 1 + i: 1 + i_clamp: 1 \ No newline at end of file diff --git a/src/wroboarm_23/config/sensors_3d.yaml b/src/wroboarm_23/config/sensors_3d.yaml new file mode 100644 index 00000000..51010a36 --- /dev/null +++ b/src/wroboarm_23/config/sensors_3d.yaml @@ -0,0 +1,2 @@ +sensors: + [] \ No newline at end of file diff --git a/src/wroboarm_23/config/simple_moveit_controllers.yaml b/src/wroboarm_23/config/simple_moveit_controllers.yaml new file mode 100644 index 00000000..a79ae41f --- /dev/null +++ b/src/wroboarm_23/config/simple_moveit_controllers.yaml @@ -0,0 +1,12 @@ +controller_list: + - name: arm_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: True + joints: + - turntable_joint + - shoulder_joint + - elbowPitch_joint + - elbowRoll_joint + - wristPitch_joint + - wristRoll_link \ No newline at end of file diff --git a/src/wroboarm_23/config/stomp_planning.yaml b/src/wroboarm_23/config/stomp_planning.yaml new file mode 100644 index 00000000..ece56380 --- /dev/null +++ b/src/wroboarm_23/config/stomp_planning.yaml @@ -0,0 +1,39 @@ +stomp/arm: + group_name: arm + optimization: + num_timesteps: 60 + num_iterations: 40 + num_iterations_after_valid: 0 + num_rollouts: 30 + max_rollouts: 30 + initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST] + control_cost_weight: 0.0 + task: + noise_generator: + - class: stomp_moveit/NormalDistributionSampling + stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05] + cost_functions: + - class: stomp_moveit/CollisionCheck + collision_penalty: 1.0 + cost_weight: 1.0 + kernel_window_percentage: 0.2 + longest_valid_joint_move: 0.05 + noisy_filters: + - class: stomp_moveit/JointLimits + lock_start: True + lock_goal: True + - class: stomp_moveit/MultiTrajectoryVisualization + line_width: 0.02 + rgb: [255, 255, 0] + marker_array_topic: stomp_trajectories + marker_namespace: noisy + update_filters: + - class: stomp_moveit/PolynomialSmoother + poly_order: 6 + - class: stomp_moveit/TrajectoryVisualization + line_width: 0.05 + rgb: [0, 191, 255] + error_rgb: [255, 0, 0] + publish_intermediate: True + marker_topic: stomp_trajectory + marker_namespace: optimized \ No newline at end of file diff --git a/src/wroboarm_23/config/wroboarm_23.srdf b/src/wroboarm_23/config/wroboarm_23.srdf new file mode 100644 index 00000000..c1a526cc --- /dev/null +++ b/src/wroboarm_23/config/wroboarm_23.srdf @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/export.log b/src/wroboarm_23/export.log new file mode 100644 index 00000000..f12be56f --- /dev/null +++ b/src/wroboarm_23/export.log @@ -0,0 +1,705 @@ +2022-04-26 21:16:19,486 INFO Logger.cs: 70 - +-------------------------------------------------------------------------------- +2022-04-26 21:16:19,505 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter +2022-04-26 21:16:19,506 INFO Logger.cs: 73 - Commit version 1.6.0-4-g7f85cfe +2022-04-26 21:16:19,506 INFO Logger.cs: 74 - Build version 1.6.7995.38578 +2022-04-26 21:16:19,508 INFO SwAddin.cs: 192 - Attempting to connect to SW +2022-04-26 21:16:19,508 INFO SwAddin.cs: 197 - Setting up callbacks +2022-04-26 21:16:19,509 INFO SwAddin.cs: 201 - Setting up command manager +2022-04-26 21:16:19,509 INFO SwAddin.cs: 204 - Adding command manager +2022-04-26 21:16:19,511 INFO SwAddin.cs: 263 - Adding Assembly export to file menu +2022-04-26 21:16:19,512 INFO SwAddin.cs: 272 - Adding Part export to file menu +2022-04-26 21:16:19,512 INFO SwAddin.cs: 210 - Adding event handlers +2022-04-26 21:16:19,514 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks +2022-04-26 21:19:01,163 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM +2022-04-26 21:19:03,867 INFO SwAddin.cs: 313 - Saving assembly +2022-04-26 21:19:05,013 INFO SwAddin.cs: 316 - Opening property manager +2022-04-26 21:19:05,060 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:19:05,088 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:19:05,089 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:19:05,089 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:19:05,111 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:19:05,122 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:19:05,123 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:19:05,123 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:19:05,123 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:19:05,124 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:19:05,124 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:19:05,125 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:19:05,125 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:19:05,125 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:19:05,126 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:19:05,126 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:19:05,127 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:19:05,127 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:19:05,127 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:19:05,128 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:19:05,128 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:19:05,128 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:19:05,129 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:19:05,129 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:19:05,187 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:19:05,187 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:19:05,188 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:19:05,188 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:19:05,189 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:19:05,189 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:19:05,189 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:19:05,190 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:19:05,190 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:19:05,190 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:19:05,191 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:19:05,191 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:19:05,191 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:19:05,192 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:19:05,192 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:19:05,192 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:19:05,193 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:19:05,193 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:19:05,193 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:19:05,194 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:19:05,194 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:19:05,194 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:19:05,195 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:19:05,195 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:19:05,195 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:19:05,196 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:19:05,196 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:19:05,196 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:19:05,777 INFO SwAddin.cs: 339 - Loading config tree +2022-04-26 21:19:05,789 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 21:19:05,911 INFO LinkNode.cs: 35 - Building node base_link +2022-04-26 21:19:05,914 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\URDF\ArmAssembly.SLDASM +2022-04-26 21:19:05,915 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly +2022-04-26 21:19:05,935 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\base.SLDPRT +2022-04-26 21:19:05,935 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link +2022-04-26 21:19:05,981 INFO SwAddin.cs: 344 - Showing property manager +2022-04-26 21:19:16,795 INFO ExportPropertyManager.cs: 422 - Configuration saved +2022-04-26 21:19:16,812 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 21:19:16,903 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:19:54,237 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM +2022-04-26 21:19:55,264 INFO SwAddin.cs: 313 - Saving assembly +2022-04-26 21:19:55,326 INFO SwAddin.cs: 316 - Opening property manager +2022-04-26 21:19:55,326 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:19:55,327 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:19:55,327 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:19:55,328 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:19:55,328 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:19:55,328 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:19:55,329 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:19:55,329 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:19:55,329 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:19:55,330 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:19:55,330 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:19:55,330 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:19:55,331 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:19:55,331 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:19:55,331 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:19:55,332 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:19:55,332 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:19:55,340 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:19:55,360 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:19:55,360 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:19:55,361 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:19:55,361 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:19:55,361 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:19:55,362 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:19:55,362 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:19:55,363 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:19:55,363 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:19:55,364 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:19:55,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:19:55,364 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:19:55,365 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:19:55,365 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:19:55,365 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:19:55,366 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:19:55,366 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:19:55,366 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:19:55,367 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:19:55,367 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:19:55,367 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:19:55,368 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:19:55,368 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:19:55,369 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:19:55,369 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:19:55,369 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:19:55,370 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:19:55,370 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:19:55,370 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:19:55,371 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:19:55,371 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:19:55,371 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:19:55,372 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:19:55,372 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:19:55,413 INFO SwAddin.cs: 339 - Loading config tree +2022-04-26 21:19:55,413 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 21:19:55,414 INFO LinkNode.cs: 35 - Building node base_link +2022-04-26 21:19:55,414 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\URDF\ArmAssembly.SLDASM +2022-04-26 21:19:55,415 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly +2022-04-26 21:19:55,415 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\base.SLDPRT +2022-04-26 21:19:55,415 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link +2022-04-26 21:19:55,433 INFO SwAddin.cs: 344 - Showing property manager +2022-04-26 21:20:28,795 INFO ExportPropertyManager.cs: 422 - Configuration saved +2022-04-26 21:20:28,797 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 21:20:29,098 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:20:29,110 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:20:29,111 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:20:29,111 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:20:29,112 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:20:29,112 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:20:29,112 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:20:29,113 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:20:29,113 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:20:29,113 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:20:29,114 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:20:29,114 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:20:29,114 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:20:29,115 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:20:29,115 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:20:29,115 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:20:29,116 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:20:29,116 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:20:29,116 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:20:29,117 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:20:29,117 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:20:29,117 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:20:29,118 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:20:29,118 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:20:29,118 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:20:29,119 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:20:29,119 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:20:29,120 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:20:29,120 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:20:29,120 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:20:29,121 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:20:29,121 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:20:29,121 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:20:29,122 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:20:29,122 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:20:29,122 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:20:29,123 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:20:29,123 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:20:29,138 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:20:29,139 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:20:29,139 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:20:29,140 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:20:29,140 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:20:29,140 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:20:29,141 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:20:29,141 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:20:29,141 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:20:29,142 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:20:29,142 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:20:29,142 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:20:29,143 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:20:29,143 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:20:29,182 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:45,550 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM +2022-04-26 21:20:45,550 INFO SwAddin.cs: 299 - Save is required +2022-04-26 21:20:45,551 INFO SwAddin.cs: 313 - Saving assembly +2022-04-26 21:20:45,614 INFO SwAddin.cs: 316 - Opening property manager +2022-04-26 21:20:45,615 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:20:45,616 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:20:45,616 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:20:45,616 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:20:45,617 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:20:45,617 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:20:45,617 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:20:45,618 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:20:45,618 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:20:45,618 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:20:45,619 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:20:45,619 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:20:45,619 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:20:45,620 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:20:45,620 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:20:45,620 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:20:45,621 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:20:45,621 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:20:45,621 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:20:45,622 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:20:45,622 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:20:45,623 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:20:45,623 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:20:45,624 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:20:45,624 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:20:45,625 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:20:45,625 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:20:45,625 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:20:45,626 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:20:45,626 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:20:45,626 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:20:45,627 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:20:45,627 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:20:45,628 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:20:45,628 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:20:45,629 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:20:45,629 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:20:45,630 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:20:45,630 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:20:45,630 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:20:45,631 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:20:45,631 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:20:45,632 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:20:45,632 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:20:45,633 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:20:45,633 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:20:45,633 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:20:45,634 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:20:45,634 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:20:45,635 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:20:45,635 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:20:45,636 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:20:45,732 INFO SwAddin.cs: 339 - Loading config tree +2022-04-26 21:20:45,733 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=sDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==sDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==sDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAsDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==sDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==sDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalse +2022-04-26 21:20:45,734 INFO LinkNode.cs: 35 - Building node base_link +2022-04-26 21:20:45,734 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\URDF\ArmAssembly.SLDASM +2022-04-26 21:20:45,734 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly +2022-04-26 21:20:45,734 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\base.SLDPRT +2022-04-26 21:20:45,735 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???Shoulder-1@ArmAssembly +2022-04-26 21:20:45,735 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\Shoulder.SLDPRT +2022-04-26 21:20:45,735 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???UpperArm-1@ArmAssembly +2022-04-26 21:20:45,736 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\UpperArm.SLDPRT +2022-04-26 21:20:45,736 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???Forarm-1@ArmAssembly# +2022-04-26 21:20:45,736 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\Forarm.SLDPRT +2022-04-26 21:20:45,737 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???WristStructure-1@ArmAssembly( +2022-04-26 21:20:45,737 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\WristStructure.SLDPRT +2022-04-26 21:20:45,737 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???Wrist-1@ArmAssembly' +2022-04-26 21:20:45,738 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\Wrist.SLDPRT +2022-04-26 21:20:45,738 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???Manipulator-1@ArmAssembly$ +2022-04-26 21:20:45,739 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\Manipulator.SLDPRT +2022-04-26 21:20:45,739 INFO CommonSwOperations.cs: 230 - Loaded 7 components for link base_link +2022-04-26 21:20:45,909 INFO SwAddin.cs: 344 - Showing property manager +2022-04-26 21:20:50,182 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:50,491 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:52,134 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:53,289 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:53,987 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:54,678 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:55,176 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:55,830 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:20:58,315 INFO ExportPropertyManager.cs: 422 - Configuration saved +2022-04-26 21:20:58,316 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=sDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==sDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==sDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAsDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==sDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==sDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalse +2022-04-26 21:20:58,417 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:20:58,418 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:20:58,418 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:20:58,418 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:20:58,419 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:20:58,419 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:20:58,419 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:20:58,420 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:20:58,430 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:20:58,441 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:20:58,442 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:20:58,442 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:20:58,443 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:20:58,443 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:20:58,443 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:20:58,444 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:20:58,444 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:20:58,444 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:20:58,445 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:20:58,445 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:20:58,445 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:20:58,446 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:20:58,446 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:20:58,446 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:20:58,447 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:20:58,447 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:20:58,448 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:20:58,448 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:20:58,448 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:20:58,449 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:20:58,449 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:20:58,449 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:20:58,449 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:20:58,450 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:20:58,450 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:20:58,450 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:20:58,451 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:20:58,451 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:20:58,451 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:20:58,452 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:20:58,452 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:20:58,452 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:20:58,453 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:20:58,453 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:20:58,453 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:20:58,454 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:20:58,454 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:20:58,454 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:20:58,455 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:20:58,455 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:20:58,455 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:20:58,456 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:20:58,496 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:22:40,251 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM +2022-04-26 21:22:40,252 INFO SwAddin.cs: 299 - Save is required +2022-04-26 21:22:40,252 INFO SwAddin.cs: 313 - Saving assembly +2022-04-26 21:22:40,312 INFO SwAddin.cs: 316 - Opening property manager +2022-04-26 21:22:40,312 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:22:40,313 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:22:40,313 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:22:40,313 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:22:40,314 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:22:40,314 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:22:40,314 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:22:40,315 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:22:40,315 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:22:40,315 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:22:40,316 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:22:40,316 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:22:40,316 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:22:40,317 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:22:40,317 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:22:40,318 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:22:40,318 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:22:40,318 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:22:40,319 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:22:40,320 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:22:40,320 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:22:40,320 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:22:40,321 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:22:40,321 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:22:40,321 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:22:40,322 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:22:40,322 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:22:40,322 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM +2022-04-26 21:22:40,323 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:22:40,323 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:22:40,323 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:22:40,324 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:22:40,324 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:22:40,324 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:22:40,325 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:22:40,325 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:22:40,325 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:22:40,326 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:22:40,326 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:22:40,326 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:22:40,327 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:22:40,327 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:22:40,328 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:22:40,328 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:22:40,328 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:22:40,329 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:22:40,329 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:22:40,329 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:22:40,330 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:22:40,331 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:22:40,331 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:22:40,331 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:22:40,462 INFO SwAddin.cs: 339 - Loading config tree +2022-04-26 21:22:40,463 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 21:22:40,464 INFO LinkNode.cs: 35 - Building node base_link +2022-04-26 21:22:40,464 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\URDF\ArmAssembly.SLDASM +2022-04-26 21:22:40,464 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly +2022-04-26 21:22:40,464 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\base.SLDPRT +2022-04-26 21:22:40,465 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link +2022-04-26 21:22:40,495 INFO SwAddin.cs: 344 - Showing property manager +2022-04-26 21:22:43,955 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:22:44,696 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:22:46,553 INFO ExportPropertyManager.cs: 1036 - OnListboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:22:49,426 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:25:55,950 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM +2022-04-26 21:25:55,950 INFO SwAddin.cs: 299 - Save is required +2022-04-26 21:25:55,951 INFO SwAddin.cs: 313 - Saving assembly +2022-04-26 21:25:56,086 INFO SwAddin.cs: 316 - Opening property manager +2022-04-26 21:25:56,087 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 21:25:56,088 INFO ExportHelperExtension.cs: 1136 - Found 53 in ArmAssembly.SLDASM +2022-04-26 21:25:56,088 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 21:25:56,088 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:25:56,089 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:25:56,089 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 21:25:56,089 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:25:56,090 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 21:25:56,090 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 21:25:56,090 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:25:56,091 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 21:25:56,091 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 21:25:56,091 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:25:56,092 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 21:25:56,092 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 21:25:56,093 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:25:56,093 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 21:25:56,094 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 21:25:56,095 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:25:56,096 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 21:25:56,096 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 21:25:56,096 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:25:56,097 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 21:25:56,097 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 21:25:56,097 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:25:56,098 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 21:25:56,098 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 21:25:56,099 INFO ExportHelperExtension.cs: 1136 - Found 53 in ArmAssembly.SLDASM +2022-04-26 21:25:56,099 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 21:25:56,099 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 21:25:56,100 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 21:25:56,100 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 21:25:56,100 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 21:25:56,101 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 21:25:56,101 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 21:25:56,101 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 21:25:56,102 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 21:25:56,102 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 21:25:56,102 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 21:25:56,103 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 21:25:56,103 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 21:25:56,103 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 21:25:56,103 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 21:25:56,104 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 21:25:56,104 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 21:25:56,104 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 21:25:56,105 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 21:25:56,105 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 21:25:56,105 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 21:25:56,106 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 21:25:56,106 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 21:25:56,106 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 21:25:56,235 INFO SwAddin.cs: 339 - Loading config tree +2022-04-26 21:25:56,236 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 21:25:56,236 INFO LinkNode.cs: 35 - Building node base_link +2022-04-26 21:25:56,237 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\URDF\ArmAssembly.SLDASM +2022-04-26 21:25:56,237 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly +2022-04-26 21:25:56,237 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\URDF\base.SLDPRT +2022-04-26 21:25:56,238 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link +2022-04-26 21:25:56,271 INFO SwAddin.cs: 344 - Showing property manager +2022-04-26 21:26:17,760 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:26:21,486 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:26:29,220 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:26:48,883 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:27:03,931 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:27:16,584 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:27:31,267 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:27:44,310 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:27:51,841 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:28:03,077 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:28:11,859 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:28:24,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 +2022-04-26 21:28:26,812 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 21:28:35,610 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 22:16:01,745 INFO ExportPropertyManager.cs: 422 - Configuration saved +2022-04-26 22:16:01,747 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 22:16:01,816 INFO ExportHelperExtension.cs: 347 - Creating joint turntable_link +2022-04-26 22:16:01,823 INFO ExportHelperExtension.cs: 1397 - Fixing components for base_link +2022-04-26 22:16:01,824 INFO ExportHelperExtension.cs: 1402 - Fixing 24 +2022-04-26 22:16:01,824 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed +2022-04-26 22:16:02,369 INFO : 0 - R1: 1, System.__ComObject, 1, System.Double[] +2022-04-26 22:16:02,373 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2022-04-26 22:16:02,374 INFO ExportHelperExtension.cs: 849 - L1: 0 +2022-04-26 22:16:02,374 INFO ExportHelperExtension.cs: 857 - L2: 0 +2022-04-26 22:16:04,962 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child turntable_link failed +2022-04-26 22:16:04,971 INFO ExportHelperExtension.cs: 347 - Creating joint upperArm_link +2022-04-26 22:16:04,971 INFO ExportHelperExtension.cs: 1397 - Fixing components for turntable_link +2022-04-26 22:16:04,972 INFO ExportHelperExtension.cs: 1402 - Fixing 25 +2022-04-26 22:16:04,972 INFO ExportHelperExtension.cs: 1402 - Fixing 24 +2022-04-26 22:16:04,972 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed +2022-04-26 22:16:05,267 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] +2022-04-26 22:16:05,267 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2022-04-26 22:16:05,268 INFO ExportHelperExtension.cs: 849 - L1: 0 +2022-04-26 22:16:05,268 INFO ExportHelperExtension.cs: 857 - L2: 0 +2022-04-26 22:16:05,268 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 +2022-04-26 22:16:06,570 WARN ExportHelperExtension.cs: 351 - Creating joint from parent turntable_link to child upperArm_link failed +2022-04-26 22:16:06,575 INFO ExportHelperExtension.cs: 347 - Creating joint forearm_link +2022-04-26 22:16:06,576 INFO ExportHelperExtension.cs: 1397 - Fixing components for upperArm_link +2022-04-26 22:16:06,576 INFO ExportHelperExtension.cs: 1402 - Fixing 26 +2022-04-26 22:16:06,576 INFO ExportHelperExtension.cs: 1402 - Fixing 25 +2022-04-26 22:16:06,577 INFO ExportHelperExtension.cs: 1402 - Fixing 24 +2022-04-26 22:16:06,577 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed +2022-04-26 22:16:06,893 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] +2022-04-26 22:16:06,893 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2022-04-26 22:16:06,893 INFO ExportHelperExtension.cs: 849 - L1: 0 +2022-04-26 22:16:06,894 INFO ExportHelperExtension.cs: 857 - L2: 0 +2022-04-26 22:16:06,894 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 +2022-04-26 22:16:06,894 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 +2022-04-26 22:16:08,241 WARN ExportHelperExtension.cs: 351 - Creating joint from parent upperArm_link to child forearm_link failed +2022-04-26 22:16:08,248 INFO ExportHelperExtension.cs: 347 - Creating joint wrist_link +2022-04-26 22:16:08,248 INFO ExportHelperExtension.cs: 1397 - Fixing components for forearm_link +2022-04-26 22:16:08,248 INFO ExportHelperExtension.cs: 1402 - Fixing 35 +2022-04-26 22:16:08,249 INFO ExportHelperExtension.cs: 1402 - Fixing 26 +2022-04-26 22:16:08,249 INFO ExportHelperExtension.cs: 1402 - Fixing 25 +2022-04-26 22:16:08,249 INFO ExportHelperExtension.cs: 1402 - Fixing 24 +2022-04-26 22:16:08,250 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed +2022-04-26 22:16:08,561 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] +2022-04-26 22:16:08,562 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2022-04-26 22:16:08,562 INFO ExportHelperExtension.cs: 849 - L1: 0 +2022-04-26 22:16:08,562 INFO ExportHelperExtension.cs: 857 - L2: 0 +2022-04-26 22:16:08,563 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 +2022-04-26 22:16:08,563 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 +2022-04-26 22:16:08,563 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 +2022-04-26 22:16:09,913 WARN ExportHelperExtension.cs: 351 - Creating joint from parent forearm_link to child wrist_link failed +2022-04-26 22:16:09,916 INFO ExportHelperExtension.cs: 347 - Creating joint carpus_link +2022-04-26 22:16:09,916 INFO ExportHelperExtension.cs: 1397 - Fixing components for wrist_link +2022-04-26 22:16:09,916 INFO ExportHelperExtension.cs: 1402 - Fixing 40 +2022-04-26 22:16:09,917 INFO ExportHelperExtension.cs: 1402 - Fixing 35 +2022-04-26 22:16:09,917 INFO ExportHelperExtension.cs: 1402 - Fixing 26 +2022-04-26 22:16:09,917 INFO ExportHelperExtension.cs: 1402 - Fixing 25 +2022-04-26 22:16:09,918 INFO ExportHelperExtension.cs: 1402 - Fixing 24 +2022-04-26 22:16:09,918 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed +2022-04-26 22:16:10,240 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] +2022-04-26 22:16:10,241 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2022-04-26 22:16:10,241 INFO ExportHelperExtension.cs: 849 - L1: 0 +2022-04-26 22:16:10,241 INFO ExportHelperExtension.cs: 857 - L2: 0 +2022-04-26 22:16:10,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 40 +2022-04-26 22:16:10,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 +2022-04-26 22:16:10,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 +2022-04-26 22:16:10,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 +2022-04-26 22:16:11,595 WARN ExportHelperExtension.cs: 351 - Creating joint from parent wrist_link to child carpus_link failed +2022-04-26 22:16:11,599 INFO ExportHelperExtension.cs: 347 - Creating joint endEffector_link +2022-04-26 22:16:11,599 INFO ExportHelperExtension.cs: 1397 - Fixing components for carpus_link +2022-04-26 22:16:11,600 INFO ExportHelperExtension.cs: 1402 - Fixing 39 +2022-04-26 22:16:11,600 INFO ExportHelperExtension.cs: 1402 - Fixing 40 +2022-04-26 22:16:11,600 INFO ExportHelperExtension.cs: 1402 - Fixing 35 +2022-04-26 22:16:11,601 INFO ExportHelperExtension.cs: 1402 - Fixing 26 +2022-04-26 22:16:11,601 INFO ExportHelperExtension.cs: 1402 - Fixing 25 +2022-04-26 22:16:11,601 INFO ExportHelperExtension.cs: 1402 - Fixing 24 +2022-04-26 22:16:11,607 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed +2022-04-26 22:16:12,003 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] +2022-04-26 22:16:12,004 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 +2022-04-26 22:16:12,004 INFO ExportHelperExtension.cs: 849 - L1: 0 +2022-04-26 22:16:12,005 INFO ExportHelperExtension.cs: 857 - L2: 0 +2022-04-26 22:16:12,005 INFO ExportHelperExtension.cs: 1352 - Unfixing component 39 +2022-04-26 22:16:12,005 INFO ExportHelperExtension.cs: 1352 - Unfixing component 40 +2022-04-26 22:16:12,006 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 +2022-04-26 22:16:12,006 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 +2022-04-26 22:16:12,006 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 +2022-04-26 22:16:13,493 WARN ExportHelperExtension.cs: 351 - Creating joint from parent carpus_link to child endEffector_link failed +2022-04-26 22:16:13,569 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM +2022-04-26 22:16:13,570 INFO ExportHelperExtension.cs: 1136 - Found 59 in ArmAssembly.SLDASM +2022-04-26 22:16:13,570 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in ArmAssembly.SLDASM +2022-04-26 22:16:13,570 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 22:16:13,571 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 22:16:13,571 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 +2022-04-26 22:16:13,571 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 22:16:13,572 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 +2022-04-26 22:16:13,572 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 +2022-04-26 22:16:13,572 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 22:16:13,573 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 +2022-04-26 22:16:13,573 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 +2022-04-26 22:16:13,573 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 22:16:13,574 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 +2022-04-26 22:16:13,574 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 +2022-04-26 22:16:13,575 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 22:16:13,575 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 +2022-04-26 22:16:13,575 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 +2022-04-26 22:16:13,576 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 22:16:13,576 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 +2022-04-26 22:16:13,576 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 +2022-04-26 22:16:13,577 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 22:16:13,577 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 +2022-04-26 22:16:13,577 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 +2022-04-26 22:16:13,578 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 22:16:13,578 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 +2022-04-26 22:16:13,578 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM +2022-04-26 22:16:13,579 INFO ExportHelperExtension.cs: 1136 - Found 59 in ArmAssembly.SLDASM +2022-04-26 22:16:13,579 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in ArmAssembly.SLDASM +2022-04-26 22:16:13,579 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components +2022-04-26 22:16:13,580 INFO ExportHelperExtension.cs: 1160 - 7 components to check +2022-04-26 22:16:13,580 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 +2022-04-26 22:16:13,580 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 +2022-04-26 22:16:13,580 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 +2022-04-26 22:16:13,581 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 +2022-04-26 22:16:13,581 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 +2022-04-26 22:16:13,581 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 +2022-04-26 22:16:13,582 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 +2022-04-26 22:16:13,582 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 +2022-04-26 22:16:13,582 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 +2022-04-26 22:16:13,583 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 +2022-04-26 22:16:13,583 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 +2022-04-26 22:16:13,583 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 +2022-04-26 22:16:13,584 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 +2022-04-26 22:16:13,584 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 +2022-04-26 22:16:13,584 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 +2022-04-26 22:16:13,585 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 +2022-04-26 22:16:13,585 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 +2022-04-26 22:16:13,585 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 +2022-04-26 22:16:13,586 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 +2022-04-26 22:16:13,586 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 +2022-04-26 22:16:13,586 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 +2022-04-26 22:16:13,635 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message +2022-04-26 22:17:26,131 INFO AssemblyExportForm.cs: 253 - Completing URDF export +2022-04-26 22:17:26,137 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found +nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueturntable_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueturntable_jointtypetrueAutomatically Detectxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis1Automatically GeneratelinktruenametrueupperArm_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueshoulder_jointtypetrueAutomatically Detectxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis2Automatically Generatelinktruenametrueforearm_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueelbowPitch_jointtypetrueAutomatically Detectxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis3Automatically Generatelinktruenametruewrist_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueelbowRoll_jointtypetrueAutomatically Detectxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis4Automatically Generatelinktruenametruecarpus_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewristPitch_jointtypetrueAutomatically Detectxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis5Automatically GeneratelinktruenametrueendEffector_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewristRoll_linktypetrueAutomatically Detectxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis6Automatically GeneratelinktruefalsesDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalsefalsesDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==falsefalsefalsesDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==falsefalsefalsesDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAfalsefalsefalsesDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==falsefalsefalsesDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==falsefalsefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse +2022-04-26 22:17:53,105 INFO AssemblyExportForm.cs: 309 - Saving URDF package to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM +2022-04-26 22:17:53,107 INFO ExportHelper.cs: 147 - Beginning the export process +2022-04-26 22:17:53,108 INFO ExportHelper.cs: 153 - Creating package directories with name ArmAssembly.SLDASM and save path E:\Robotics\WR\URDF\URDF +2022-04-26 22:17:55,069 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\CMakeLists.txt +2022-04-26 22:17:55,070 INFO ExportHelper.cs: 166 - Creating joint names config at E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\config\joint_names_ArmAssembly.SLDASM.yaml +2022-04-26 22:17:55,071 INFO ExportHelper.cs: 170 - Creating package.xml at E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\package.xml +2022-04-26 22:17:55,071 INFO PackageXMLWriter.cs: 21 - Creating package.xml at E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\package.xml +2022-04-26 22:17:55,076 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\launch\ +2022-04-26 22:17:55,078 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\launch\ +2022-04-26 22:17:55,079 INFO ExportHelper.cs: 187 - Saving existing STL preferences +2022-04-26 22:17:55,080 INFO ExportHelper.cs: 450 - Saving users preferences +2022-04-26 22:17:55,080 INFO ExportHelper.cs: 190 - Modifying STL preferences +2022-04-26 22:17:55,081 INFO ExportHelper.cs: 464 - Setting STL preferences +2022-04-26 22:17:55,085 INFO ExportHelper.cs: 196 - Found 0 hidden components +2022-04-26 22:17:55,085 INFO ExportHelper.cs: 197 - Hiding all components +2022-04-26 22:17:55,336 INFO ExportHelper.cs: 204 - Beginning individual files export +2022-04-26 22:17:55,339 INFO ExportHelper.cs: 270 - Exporting link: base_link +2022-04-26 22:17:55,339 INFO ExportHelper.cs: 272 - Link base_link has 1 children +2022-04-26 22:17:55,340 INFO ExportHelper.cs: 270 - Exporting link: turntable_link +2022-04-26 22:17:55,341 INFO ExportHelper.cs: 272 - Link turntable_link has 1 children +2022-04-26 22:17:55,342 INFO ExportHelper.cs: 270 - Exporting link: upperArm_link +2022-04-26 22:17:55,342 INFO ExportHelper.cs: 272 - Link upperArm_link has 1 children +2022-04-26 22:17:55,343 INFO ExportHelper.cs: 270 - Exporting link: forearm_link +2022-04-26 22:17:55,343 INFO ExportHelper.cs: 272 - Link forearm_link has 1 children +2022-04-26 22:17:55,344 INFO ExportHelper.cs: 270 - Exporting link: wrist_link +2022-04-26 22:17:55,344 INFO ExportHelper.cs: 272 - Link wrist_link has 1 children +2022-04-26 22:17:55,344 INFO ExportHelper.cs: 270 - Exporting link: carpus_link +2022-04-26 22:17:55,345 INFO ExportHelper.cs: 272 - Link carpus_link has 1 children +2022-04-26 22:17:55,345 INFO ExportHelper.cs: 270 - Exporting link: endEffector_link +2022-04-26 22:17:55,346 INFO ExportHelper.cs: 272 - Link endEffector_link has 0 children +2022-04-26 22:17:55,346 INFO ExportHelper.cs: 317 - endEffector_link: Exporting STL with coordinate frame Origin_wristRoll_link +2022-04-26 22:17:55,347 INFO ExportHelper.cs: 322 - endEffector_link: Reference geometry name +2022-04-26 22:17:55,506 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\endEffector_link.STL +2022-04-26 22:17:55,923 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:55,923 INFO ExportHelper.cs: 317 - carpus_link: Exporting STL with coordinate frame Origin_wristPitch_joint +2022-04-26 22:17:55,924 INFO ExportHelper.cs: 322 - carpus_link: Reference geometry name +2022-04-26 22:17:55,969 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\carpus_link.STL +2022-04-26 22:17:56,017 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:56,018 INFO ExportHelper.cs: 317 - wrist_link: Exporting STL with coordinate frame Origin_elbowRoll_joint +2022-04-26 22:17:56,018 INFO ExportHelper.cs: 322 - wrist_link: Reference geometry name +2022-04-26 22:17:56,031 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\wrist_link.STL +2022-04-26 22:17:56,058 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:56,059 INFO ExportHelper.cs: 317 - forearm_link: Exporting STL with coordinate frame Origin_elbowPitch_joint +2022-04-26 22:17:56,059 INFO ExportHelper.cs: 322 - forearm_link: Reference geometry name +2022-04-26 22:17:56,112 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\forearm_link.STL +2022-04-26 22:17:56,168 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:56,169 INFO ExportHelper.cs: 317 - upperArm_link: Exporting STL with coordinate frame Origin_shoulder_joint +2022-04-26 22:17:56,169 INFO ExportHelper.cs: 322 - upperArm_link: Reference geometry name +2022-04-26 22:17:56,180 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\upperArm_link.STL +2022-04-26 22:17:56,216 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:56,217 INFO ExportHelper.cs: 317 - turntable_link: Exporting STL with coordinate frame Origin_turntable_joint +2022-04-26 22:17:56,217 INFO ExportHelper.cs: 322 - turntable_link: Reference geometry name +2022-04-26 22:17:56,290 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\turntable_link.STL +2022-04-26 22:17:56,359 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:56,360 INFO ExportHelper.cs: 317 - base_link: Exporting STL with coordinate frame Origin_global +2022-04-26 22:17:56,360 INFO ExportHelper.cs: 322 - base_link: Reference geometry name +2022-04-26 22:17:56,369 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\meshes\base_link.STL +2022-04-26 22:17:56,393 INFO ExportHelper.cs: 405 - Removing SW header in STL file +2022-04-26 22:17:56,394 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components +2022-04-26 22:17:56,648 INFO ExportHelper.cs: 145 - Resetting STL preferences +2022-04-26 22:17:56,649 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences +2022-04-26 22:17:56,649 INFO ExportHelper.cs: 228 - Writing URDF file to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\urdf\ArmAssembly.SLDASM.urdf +2022-04-26 22:17:56,675 INFO CSVImportExport.cs: 32 - Writing CSV file E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\urdf\ArmAssembly.SLDASM.csv +2022-04-26 22:17:56,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,718 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,719 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,719 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,720 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,720 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,726 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, +2022-04-26 22:17:56,727 INFO ExportHelper.cs: 234 - Copying log file +2022-04-26 22:17:56,730 INFO ExportHelper.cs: 439 - Copying C:\Users\Payton Jackson\sw2urdf_logs\sw2urdf.log to E:\Robotics\WR\URDF\URDF\ArmAssembly.SLDASM\export.log diff --git a/src/wroboarm_23/launch/chomp_planning_pipeline.launch.xml b/src/wroboarm_23/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 00000000..34271389 --- /dev/null +++ b/src/wroboarm_23/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/default_warehouse_db.launch b/src/wroboarm_23/launch/default_warehouse_db.launch new file mode 100644 index 00000000..2543e8f8 --- /dev/null +++ b/src/wroboarm_23/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/demo.launch b/src/wroboarm_23/launch/demo.launch new file mode 100644 index 00000000..9abb2e63 --- /dev/null +++ b/src/wroboarm_23/launch/demo.launch @@ -0,0 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/demo_gazebo.launch b/src/wroboarm_23/launch/demo_gazebo.launch new file mode 100644 index 00000000..a9f320c5 --- /dev/null +++ b/src/wroboarm_23/launch/demo_gazebo.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/display.launch b/src/wroboarm_23/launch/display.launch new file mode 100644 index 00000000..ce58753b --- /dev/null +++ b/src/wroboarm_23/launch/display.launch @@ -0,0 +1,20 @@ + + + + + + + \ No newline at end of file diff --git a/src/wroboarm_23/launch/fake_moveit_controller_manager.launch.xml b/src/wroboarm_23/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..46689c86 --- /dev/null +++ b/src/wroboarm_23/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/gazebo.launch b/src/wroboarm_23/launch/gazebo.launch new file mode 100644 index 00000000..cb085009 --- /dev/null +++ b/src/wroboarm_23/launch/gazebo.launch @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/joystick_control.launch b/src/wroboarm_23/launch/joystick_control.launch new file mode 100644 index 00000000..9411f6e6 --- /dev/null +++ b/src/wroboarm_23/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/move_group.launch b/src/wroboarm_23/launch/move_group.launch new file mode 100644 index 00000000..bbaa5eb5 --- /dev/null +++ b/src/wroboarm_23/launch/move_group.launch @@ -0,0 +1,105 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/moveit.rviz b/src/wroboarm_23/launch/moveit.rviz new file mode 100644 index 00000000..6a876dde --- /dev/null +++ b/src/wroboarm_23/launch/moveit.rviz @@ -0,0 +1,131 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.5 + Tree Height: 226 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + 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 + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Name: MotionPlanning + Planned Path: + Links: ~ + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: ~ + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 2.0 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.75 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.6232355833053589 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 848 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1291 + X: 454 + Y: 25 diff --git a/src/wroboarm_23/launch/moveit_rviz.launch b/src/wroboarm_23/launch/moveit_rviz.launch new file mode 100644 index 00000000..a4605c03 --- /dev/null +++ b/src/wroboarm_23/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/ompl-chomp_planning_pipeline.launch.xml b/src/wroboarm_23/launch/ompl-chomp_planning_pipeline.launch.xml new file mode 100644 index 00000000..7318a0b8 --- /dev/null +++ b/src/wroboarm_23/launch/ompl-chomp_planning_pipeline.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/ompl_planning_pipeline.launch.xml b/src/wroboarm_23/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 00000000..1bdd6cfc --- /dev/null +++ b/src/wroboarm_23/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/src/wroboarm_23/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml new file mode 100644 index 00000000..c7c4cf50 --- /dev/null +++ b/src/wroboarm_23/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/planning_context.launch b/src/wroboarm_23/launch/planning_context.launch new file mode 100644 index 00000000..b5f6954c --- /dev/null +++ b/src/wroboarm_23/launch/planning_context.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/planning_pipeline.launch.xml b/src/wroboarm_23/launch/planning_pipeline.launch.xml new file mode 100644 index 00000000..4b4d0d66 --- /dev/null +++ b/src/wroboarm_23/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/src/wroboarm_23/launch/ros_control_moveit_controller_manager.launch.xml b/src/wroboarm_23/launch/ros_control_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..9ebc91c1 --- /dev/null +++ b/src/wroboarm_23/launch/ros_control_moveit_controller_manager.launch.xml @@ -0,0 +1,4 @@ + + + + diff --git a/src/wroboarm_23/launch/ros_controllers.launch b/src/wroboarm_23/launch/ros_controllers.launch new file mode 100644 index 00000000..7c953597 --- /dev/null +++ b/src/wroboarm_23/launch/ros_controllers.launch @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/src/wroboarm_23/launch/run_benchmark_ompl.launch b/src/wroboarm_23/launch/run_benchmark_ompl.launch new file mode 100644 index 00000000..abea39b7 --- /dev/null +++ b/src/wroboarm_23/launch/run_benchmark_ompl.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/sensor_manager.launch.xml b/src/wroboarm_23/launch/sensor_manager.launch.xml new file mode 100644 index 00000000..c12a65c3 --- /dev/null +++ b/src/wroboarm_23/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/setup_assistant.launch b/src/wroboarm_23/launch/setup_assistant.launch new file mode 100644 index 00000000..da7b439c --- /dev/null +++ b/src/wroboarm_23/launch/setup_assistant.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/simple_moveit_controller_manager.launch.xml b/src/wroboarm_23/launch/simple_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..7a92fb9b --- /dev/null +++ b/src/wroboarm_23/launch/simple_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/src/wroboarm_23/launch/stomp_planning_pipeline.launch.xml b/src/wroboarm_23/launch/stomp_planning_pipeline.launch.xml new file mode 100644 index 00000000..a1676cb5 --- /dev/null +++ b/src/wroboarm_23/launch/stomp_planning_pipeline.launch.xml @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/trajectory_execution.launch.xml b/src/wroboarm_23/launch/trajectory_execution.launch.xml new file mode 100644 index 00000000..20c3dfc4 --- /dev/null +++ b/src/wroboarm_23/launch/trajectory_execution.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/warehouse.launch b/src/wroboarm_23/launch/warehouse.launch new file mode 100644 index 00000000..0712e670 --- /dev/null +++ b/src/wroboarm_23/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/warehouse_settings.launch.xml b/src/wroboarm_23/launch/warehouse_settings.launch.xml new file mode 100644 index 00000000..e473b083 --- /dev/null +++ b/src/wroboarm_23/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/wroboarm_23_moveit_sensor_manager.launch.xml b/src/wroboarm_23/launch/wroboarm_23_moveit_sensor_manager.launch.xml new file mode 100644 index 00000000..5d02698d --- /dev/null +++ b/src/wroboarm_23/launch/wroboarm_23_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/src/wroboarm_23/meshes/base_link.STL b/src/wroboarm_23/meshes/base_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..c298f6b589bed4d5547bebeb7d6d33a87c54cc6a GIT binary patch literal 11984 zcmb_hZHyjO8J#R7f~8vpexM12?E6wQYSI8kC_C>662%6M8d6AVqX{IG$|jbExRywz zu24%G(5%LfDzrO@3urV_qs`7cKxlw8SS++gBZd$(TKpgqu_k^!ANS0AX6Ig(AHIKj zy3aY!nYka&y?1Vw{eORdk#xVf^1a2LSKe0aU$?rPKkezf9^akIzZU~PHu2!zSHH3^ z|LE%d`Dq)U+M8A|3s^H{*$F50i)-$2}@6qkK!@avVIEzZ3DOC?8uHSa?!@0r}PH5=?+SS}tZ z1+#$N<1KIfPChlcwdg&zv*ZY{=AGHRqFi&z*xPgu)c@1TQ%wrX{)G$S-|cgJvc<4a|BrXL;AlOjjNP`S-|cgBeBNV z2}@NG+*ROE?0o^IVvf))=iT zR!gD^W&yiLmVLfP6%3I|Bh13z#bZLbU4=#>iuP00QWN{gCI7;sQgwKzO5RC4!kc## z%mUU-R^hZiYN?5RjsR=k&^MLzjd+Cq=qQ*4>>gp1)KU}s90At6VT@HW#(Gv0btHBa z%mQ|gFxqRWiG7X$Yu+$dDw!+dky0=V*ge9mt)(XRIRdPC!<-+=oEMLjf?2@s5voru zHL=eTV9h(T`Ocoy#G%wK@kl9{1>AUO-8B!60Bc_H)7l>1Bh=lFf?2>#Tj}~?ZN(8_ zeGh3jU86#Og!QANU>2}@NDt~dXnoERVC@g-e_dXvdX{_V4df})P0xLm1cj{Q7{YG zJ*2`FR1+8P;ZPs#?_PIf3XO1HV6Ao``>I`iRUW-?Z+`k$pI=b-^X{L`56{1YJq))M z$hBB;^1`k8lh1x~2?evzZknm>!4X!BU3_I;|Mj+r2P>F`{_lFon^$=AnPc-+Z`1p% z6@;m)TEv4RtXMYvKy||px9OU)=sj4$tnl|dsjvtu#-I6ab@K~*Cc6rLLwSkM<(~}D2%f*MlRhxP8ai*aD)}_`qK^7JGV?Pple{?^;5^tT3h{3XZVilneg5 z@Z$QrmryV(%*}{G`XEQINpI#@0i>Urok6Dun+PjpEyRHI;4@Tlb9?y9B=i?Bl0 z#2l+=^r=k2EZ%*z72GD=R-sl7x=+OsR$TDPtqb#aelOCxtY8+tYjiz0!U}zMSq&l{ ztYDUS>)9aw9<2!Sir-}NJsJhGqz(0K5P2$&utM5xGCp=$!7P~tdNzo7aD){ySMvBA zWCgQiHrw~aZhvru6;fmDD`!{15mrc*$dlEl$;B+m-OQWz*yRW-q}t`lD%#{?7SI32 zqtve;s6P5V33EliUt#y*=UUUO+GPrkup*4aa7txGXk9y#g}$*fAgkL?#gRn{I;FA) zD+D*J*Y{Mc4m}%AckICtR$%_?x5f5*u!32b&HBZ&t>8#_cKfEwnc51Dup+cV`0D%` z?_qOW`yBH|$3oj9JiGO6cys$wAl|z73AX@?JemkA!gvec09e5uoR`O2`>8m>3ar}t z{W7g!R(Pts`{tN~d=l2vZ)o-So7+4OUp8%pBSm^#S+0=RSg1<+ z!1iS`v|IeCv1I;hPNiIY(I09wk42@zVUjzOD7f-yHAZ>~#G1 zr{*~0C|~od2xDikCcL0!0xf>x;NI>e*CI> z`_8F8M}RdiPA~3}QZNhHJ;vr&)%U*tqWX&USM)gota)*IagUUOS-|eGV*5wxZ`^Wv zea^vNpCiDU7v~-KNGX^F>>lNF8|pPbdUiPetz$io0Bc^Hque80!jcw)MKdgG?y z8RvYl#}Q!7i?2q(BcWgxuzTp-$bNTeb@e~jPH+TR^Wv+Kd!!W10(Os=ul-#8@BMEc z+%r6Tjw8UD7bi>iNGX^F>>jf(ZK^+g(|v=t|Kz8090At6IDfiFO2I5(_c;3F_4Sxs zAB?S9UUCFj^WyyJ9w`O0fZgNJ^dI17k zSe*ar`jR8SnpbwRcCK}gl!95n?s4DlW5b{AxTfg;YfH%yV9kp&m3yQV%mQ|g_Y`*x z*Y3Hgc2}@NM$Hc zOE?0od8Mw{w;K0IDVPQ99#Y{7)I^Q|YhJ03_6^8AQVM1PyN6Wj0=1nZz?xU;ynQKh zkCcL0!0sU{PJuOwBfy$h)+_r`Bd}6x5TFVh&%`5A!-E6r>O2I7P;PKps z0(%CI0Bc^^KiG{~@JJ|_1?(QOlPR$G;Rvwim3@%itGP!?!7O0+kR4fpJsd}XHLvXF z>|V`1QVM1PyNB#73+zQX0<3vuUuw5Y?vYY33)nqmhdjWZnj^rPSN7L-yW}1z1+#$N zLw5QDoDDbvta;^}V7E)|ky0=V*gbG6(i00ufHg0leeB$oW#PUSk?xaZ+04lk6aG}D z2?}W+yM57!yocTPfE8D$8WC2=6WVpAT|N8XxMevwha3R$V`=BMkSV!Q{lxJ8sBzu>_;B>gk*;gCuHF2BfA>7SvHOm=VZ z+E2wSZV}BSzu>`p5#IYKW$CA41@F#OEx*WnFl%v(j1;`;^DaY^F8x%j;C+y) zW^s$S0194Tc|BLw(oe+--f^@&I2W_HMcN8p$#~`DOl<{6Six(1TEQ%Ck+y=@3|^zy TyRF~|D|i)6E11PCl4bt`R@fV) literal 0 HcmV?d00001 diff --git a/src/wroboarm_23/meshes/carpus_link.STL b/src/wroboarm_23/meshes/carpus_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..412f53228123ce4518b201d7ddc6251cb1b95cec GIT binary patch literal 50884 zcmb__f2^))b=3*w*B?_EI!bCSc4+S0u@(huv3AaP?&(BI#!Bl@utsAIiZdbwu~BOi z6~`1MBr-sZhFC*LoVnA6=s>k(!uifQQ#32Tx-8;?RUMu zzB49Ha&q>3d#$~mU;BBU_r3Sq_vq;V?|)zUI>vk8^62O**N=`~d&f`T_S7CfJN>48 zeEko9Cx7qnyYE|ezi|1i{gNS%S!CGe@7gJ(wb_hzdq=9F zwnu%*$nk-F#t|h$KkKccw@@?28E12;;aK`zDB5V%9;;-9VGmL0?H=<{{cxni8dJu- zd!qT@V(oT6FuH|O{ObKCqrAzG-q~S>QPK0#oVH3mm&Q{ZE89=2RU<=lv!ao`G|D5( z->d!DnUxIK%)zS}g;E4&a53KXFqCd`UY>l;$Ih<3PIer^6a<2`u191W(*qXQS4%T>D{-Tz39P@tT57(jGub=p1baO=P#}> z(vu9>)SC2TXw{6-s4w6D#^X2Lc>hFW((@W!_32Dnd;gyH+@JDyGSt6fZ!;2w2-OEh zS}@v^4E1kaqZx@(&sP}fdGU?Mj^BLW-R^lu+HTd1f&KP@Ylr&*Z==-n(plAT3z{Ll z<4uiXBx*kA51it3Mt;2ZVXAA_->W5+ck@{&8~``lp$=A1DfiYWU{#(qGJ47Kp= zFvBRa)xXks*Bv-(anpa`RO*V~JKQez$Ljfn;a$xmT-8Mj>NQoH62* zA(AcP&o0iA86!Q(Aj@oy?%4Agqfv1Z%{0=Jakob|`w^$JwW?2U)sbhApOz;XaqpV7 zO6X!F%2C+TRgE1z$%s4LjFBF-%Gp%9snIL3J;~6B6x*#@G7`nu{#h{ElMK!5x<)e+ zHD8IhJc4Y(^YcB|rOdwYhwS`apR-jHMtwR%npx~(+&P>G_uN!mBJzjGLi6(lqdmb& z#-5Dl-udUg`R||GvvT%6lR|w@t=Zu7BcR|M2P8zV@|Z*h7u9y}KS} z7)1@+Wc>W~vv*uO{ky;C<)`VPhEeKMp9b3uAPY70Z?LKH!1b5E@X;GT^Ul9k8b)PY z+CF^_GmN5!Z8FBaBt02dHg8UyQNwCqVH8TAH{<9g`f=fYK)pN}mo|RRd~$9xjG~5Z z_TxP_F&~$n4}0*tQM55P{SIK8VH7oNQ{yu?v92z?uI$OUw6VtO4Z>lDQPi+a#xozm zYQOYqwD1b>ONO*if*;WMS3!B=+$|?%}@)^q94WhipQ!njLNvQHHMYv z+YFi_e76Xc``0-%wWH*-DVg? z4ci>6&vuRMR$uLSSWNy|uIL*OaiOJA9UeQQ~QPl7{UXB%3N$tBt zF@wCWJhMxNJ#z-LcXI~&lrf5Iub8Dq&LCP;b4`Y4bIGuWsAOQ=YAqjT7)3VbsZX5g zeAq)&GPoad4JlfQTI2TqWezAdpY$NcJ^1 zZf2C%*vQzeFpOfPC*FGd$)Eq~Tcz>9zxl?~iyQxl#`I)d+FtobN3X+5G7VZ8HC2UTa^s-qflz? ze(VQwq-o+MCM3(GA?bc{9rIg z<_x3wxw1eEWz=PQGA?ap@D&WB7)jZTdFOm+XDAJOGA?cHMAFz|7)1^3O42}XaEB`m zdonIi>#N79pVX>$i3azy6`PlE-+C`RIaXvh(rA3Sl2VNb@D zo}N-Ux;&%Ys$_5{V2-G@JO|Ye-mTnoosj1lmp1n*uKr;Lb=JBc6)REH;9kW{=sD+| zp&0fggEseEuKvReqo~0>mpL*pc(-DXq$lIj#>%f885leX))+=H63-6i$iM)aH?qno zdonI<^r3R(FvBQn@C;-o3=E7D@1oAy@?>1vn2XAh!wjRSfw`z085o%FQ|3r|GA?c2 zNx1q)hWA9rN)#jUPQn}+7`(-JZ?`8IwEe`|=f|n{_GB1E4L>uC44+ZHHmE`%OQ8=o}>Dzkd54y!;bC^y(Yx zVR@24`-%5H|NJfA`=h&~qkF;l6);}C!Z1psuJfFXzw*}GFCTl)`%6RT$1da2e#YT6uDG#8#2zd zY1or-X=5(-7;P{(x<3QP8&()bQA4MM7~lUxufD)6mWDkUmo`?*8CDG#TqUmphEdee`GJ0LB{DaVBgL>M%~WL(-qZaj|nqRbEG z26AM$bw-MHO701&JX5DG3?2>w6*fpD&_`q zWWg|s8ooshJ?BbCj$EcER&ZS7ZJ==`{W z99b}oVkF;c2L^M4w}A9yT-w@Ep`r8R26AML+8gia-p zU~YJHb#k63ijj0`i^1IB9Vq4VQ{cdYbeT-sRq zyk99lm>axf%^61VbKS4RU~cfnl%9-Bn|)v_`}|mC7{y4s4T7QbdGk?|E37Glo5L2H0n0FEwV2LP=X$yV9!iNTV5l;|qU!|LhN+tY~nSI1gkPMSINJ zxrRM+#=HK@qx%p408p$w=>|xww=rmZ-NQO~lV+YZDhWTD%4^hd0>wSW5y_ydVY*dSYe=5<&j1+(5D?v zoGTbck&SuMdxm*G>>(-{81)@aoE42^7)3VLo8B|bHS8fO8CWqpoH#2Q$uNp+WP#o@ z%r)#GDj8V$Cpd9dG?HNy*~tIu%Q6S;Au1Wj;1irUD|wy_qsYdtRCBV_u!pE*VDCD? ziL;`S45P^An&JvtYS=?mGO(kb;KW(cNQO~l<6ObW@;$?RKI|bX88}O7E)Fw{ihkg} zJJ(RF&Z-}Z8+!Z047IA>IcN-581`h`(i`UE3Wi3vG_)3081`gb+M53>7)FtyHNC>H zC*#uAIzC^HRWghsL%F%auqWfvRz6U$Srri?5-a>ea8#`(T(&Z zgSIo6Gq}xY6t!b7dG4KW`nLN{pZu=RmWDkUm$r8zYHTwa1&y}B_~P|Xe%~ukU-61> zI%PlX$+)z=qf%p=(I`Y}8;qx}zvgef`1D`BMx&t7HW&|Fzxf-F-T3<-`m3d3PsXL~lbRaaj7CADZ7^=X z{)ykWyK(zNf4em7$+)!hCbP|G6g1j~2ERWzeCwBUZcoOQ&FAP7U=K3})DWo|FMSyO zxNtw9QJ#!T8~x++d1-7j8a0enGoE)7^Ks$%Fe>BH#ys))yfn5Mje2nZ1&y|$amypvcQ3u~+LLi< zW2ffxd1-7j8U>BEp>gXYI1Mg+8rYL@OD~?!w;6suXQs7X{gB3adNOY4)t%uMw`##q z3-^rFc8=9WdNOY5#ru*Ts|7}KjkcjNR{r9g+mmr+ zANw8hLB@a@A~oZscj&CGen6u<8J9Nt$0z#g$2Ox;!&o)rdA>7vtjd#dX=9%FL|+=) zj7CADZH(0$efRO4SFDUn8|#fv^rf-QXcRQshQ|ARhbs+xGA?c84WH;sW1G<^XtWKD zkNYlK8unyd+Q@%C(brzG&1e)f+J?sGuj@`-`;|Qzmp1k>KGB!PHltC{Xd4=R)AycO zu`(`g?9_asANF=XO)MCVf=1iW=qHvs4eZIdr58{1+YCR^Gt>O+1Bp>%@l<3+=+H$D6qp;A(dDiG&G3WmNAp4OF&F0FwN=Bo=?h#qE zsy#p@Lp$F}&y&$8uzREz8W<~n@4wbA#)r>NwPR=oSJqW~5H}es58JhnUjbty6Q6IleKA(@lGsGQkNU)V%=jg_4wRfyU z!Bz&ZWK`ya=Ega=ksqBoh?@+ITi-0Ft34Tw0vlsEjL4!N?Exwo80o%?PBoIzD6qBr ztc(?I0345pI3L)9hd(oi-I=y%ReNR(?7@6%urj*IXcX9;!CM-~(JEz^TDxGZ^rINK zaa6BCn5~jzG%EYFV01nMrJbR&Ry)RSsnMPpLp{HO(I~JrhAVfU_5hU(jr58}G8zT8 z=D!%XxLVJR-}{0$tlblj`8gu7ichub=uX#%n|Ow{4=C8m&C=Lr7{y4oIl5!Dw}~g? z!d4cP#x}z!MzUQq=$cNa6Hms4t!y4fcavchBiW|LSRZcU$+&~vr@=u+p%keZ&v1>c z>Ic*ZPsW9fp7Zum{n%z0r4ebySnX}%$+)mP3()gzhEa@Un`1TBhnsjZF6>^@2N^~& zl5J`{*R|VfwYMkZ!tNd8Aj7C(M8^H9H7+Kej63Sp6U#P3Ej){U6yxX-)zT{sqqvKv ztGi+YGI%{V*aUW32Wz@nl@sTGQ2!ZH7^dWSjjM ztG!J;8F#Rcm-XRR7=_a3&3J})hRca3+r*P`VPkIkeznao zijiznW2_H1@nl@sSYzDhYb9r&^;% zy*ky#`&ITlTSyys3$|$Zn;d<6P0yUsdZ0};9E%L2g1yozuWF)T_eyjm_Iz6-8M&^u z8AeerSILy&9Y?5onxy^oT7|gHfF4hrAs`nX`7vO5{(opyGN8w2oU2<^ zD9s?(aWTd`$2V{H&I!catA(s!*Eahx?mp>B25q&Fvv`1E6eHOtW86j4lW}R|hkYuI zZH7^dWSbh3YN74PxU`+YhZ#mu!!{Y?IhdY|E4wr5Afr%<)Qs_TPEW?Ajh`{keS2lq zQ?|EaC5oRXW4vXgCmFOcgSD@)=i3aU7|AvnlWMx{$+)z&OH`h3GmN5!ZEB3SzVu{V z+S*r0IKVJ!7?Ikqu90y|-*?lKaYL_8oNb2M&Kh*?M={2GdwMc1ZH;c_`8LBSMzYO* zj87Bk$+)!f!*x{}+YF-^$u>2Pyb@2-lW}Qlg_g!P!zf0wO^Na8E-MZ8MD0h%{q-+D=c#rHvWnU9`q(n_(0q*=DOIb?DoZacN^! z_M3@qhEde8O^rz%;r3))+CGU6GmIKWWbO8vo{SrMvpWMBu1%!2?|Ji9q&-?xc|P7U zQbUZotJ5B9a^#(X9`CyYd)S?6yG9OsKGn!pxv~)%+9g){VGmKsaLuBnMly^dTRQ`L zKWmjeL?y#Diw-l4A{%ouo>6@lO%Ls4xMtB(!?DOPiuU&Cs^_)WYNX57KEFQawHg>V z8AJV`$FE=*73`H6^iCFSXRS$(Rpt3~m8j>1Qg6%FC|toXiW-{P6$VG8pRiz=d ziu)BuWwuJts`AVk&{GYeLky$TD(-MA8lGFCTm_1@Gi})_d*%$ZrRqo@W*8-n8j)2- zk5w{U-{~;JC~Ba8s_8TzEAKKyx%Lii?~h9jd*%#9s$0fdT(nLsT-fW2|T-!zi*nH&wyxloiZW zkL-M?8*{{3#ht16*8jOG)9eQZ>#C{NWP6f9TO%C|)m57?jG~4sx(pgoAFe$am$v3c z8e0sbsNsq(g9hu|sn%qBGA?b6v^1hJ-h^QkHO5*ms8m>$ja7ZGJsFp__xzz%QLk^p zFp3&utru#r4y)=8wkPA#)|{&!TMVP9G1hvahH4eFibs1gE^TG7G@^dugkcmTxuVO^ zbJn<1Rmb*ZT-v@3RAoG_TUU;pFpQ!G?V+B<>(CF@>Qk-B_GDb?u?n&J!Q61G94k@k zhibiWtW>MG#>$mjl0h3I%^VrW%5^!bwg+o`Bub;sTE%F!=A5;PJs;&s25qdEItvdo zjH1R^>xCMsRa_eOWL(-<`SsIlm$ix)45O$q)_S1^(W*7so{UQy8C-oCG`1K5@Epa}u3E*c^)g`?#m~oDFJ`FLWP37h=;5q&tC)uwD^a1n8+*=r ztm#PxZH;s=xSz}!M)7lvp%|LMV%U>$X=}w?!7z#%T32FlC9)oCdNM9;t^8ncf1fjq z;^)c_F_;_BIZaQ-rL7FUf?*URDVyhNi(wQsRGUf~s#RPX z_GDbz%njb}hE_2*c+<#OiQ?zlU8TX?;B6*7$)K&10UBKG+}n{O3x-jQ#QXJdFVgwJ z6Q>yVWL)X73bFdZ+;FRsp>uGj)~ePd=R>uM-Kz3rT-q4v9ajH1R;+HkU>HRWo#*46 z^UhEVdonI%?(+JnXx!zf0=u5`kY9~hiH-m%h? zacOf+an+0r?}?6;C`Qt~T^d}4-rMa-25r9y>GPxRSQ#r({M^qBBg1EuJ;?|?oP(&P zcd1&%bw>Ft!nZ`uQ4iuA-`!`e$v(RVhH4dGq$e4)QR(3v)dludyX}&d*i>t>V zK2)oC!7xhm!HUGt;JQ++;$rChU}e0HOWPGhhE<|k#S4Z})X*sb4d#bx6&J&vj7!^f zO@>yfR`G&i6g6~8D9=@^xH8I~j7!@UU4~YvR`G&i6g6~yXlJ;8s8#H&Jz@4_T-vTo zGxS5XiWdx{sDZiQ`JsMbhhwecV%U>$X}iMCu-a9tc)>7=8agGQ!JS&Qiv2Wk!W_xC zw1-MT{98!O57jDOFpQ#xPl+KvRIAue6DPjPsXLK6$6IOkE-XLu@c44$9sv+kE-XL zo@CJ0%2%sYtGHU_SczgJ-=c<|t5)%8dXhm~8H~ANtH@xE%o#@Ub7eCaIzL#exES_i zT-w@+z~FqajyH28VjPcmq$QVR+X zlMLEAKcJ!WgSCnm45O&wXNEpMSgW`g_GDb?@f=h?RI7Nw&^cInqti|d)hc$Y_S^+B zE^VFEU~oQEt9ZdMN@K{kRAQ)BaWS}y(UWm$W5w`Z0tQzJ>v*fyz3&FaFp3)7S-GzJ z{9vu((y%Av($>vM`Jr0H3x-kD(EUmb)he!xvM1xxMjt9i`uwOI$ykZv=jcP_$k21- z2JcwT+VUiWHg=-Qkzqbmt9ZdMiW(U4%8`MgTE)e%C*#t_nyMTb@>>(-{>)+JNShS6z z?Yq{pANI@{>))KrShS6z?Yq`e!=5<<-$d&g5YstNhEZheY~L?6>>(-{`0iTQfS76| z!zi+KM_E~k_7If}eJ_2bRmm`lY~Qt({ji6qWOP*oP^SGzhEdTE+{oq(wTg9w&yyiN z>0zkU>HS)vS5W_PsXLKm5)Raj#5>2mt*Bv zjGGMY+AFO}hEZfQwlZOsANCNH4A^I`j5l40Ge)7*bKT+QJx8m`BaLRDPps9j-j8M& zMKk4ibgVwA{$x2cVz1sRUV>} zfn4dzc+>fCEHaFujr`XgZr%@j<_zR~SH_!aB*Q4OF&DbS%{A;HDjC?j_#O9^o+ra7 zvauiQ4ma1Zhp1#=5AMo%(|#nwD6)|o=ZHT0yPWBvoeX{7{R)OrWJ`PfHTV*1`(Ip6Z8c8PL}JU%@bn46W%E zhCLaVwpKpJZZ=lQFp3Q2<_g1}j7wYjcm=~KGPEnLFzm^=w6(8X!7z#p?XD{fdonI< z?T=S5j3NVrs&~lq(X}Vz($@L0qLB=v#HiYI@Q+owSVLs(7PjZ-So!PK#oEKTM$yJP z?)&bfg4sHX+QFDqNo!BWrHysm_x5c@qoC0?dOoT4)}D+@8|%1h&}}ms1&y|$F{xVD zo{UQy>v*UXbCA&}XtWK+r21ZaGA?bbc7#$QV$AMl&YWDLXqeE^X&L8a1te zIbk$v7^|V)78sK%n;k3T()Qj(jcrDwpwTuMlWL*u$+)z=2UBC4(I{xN4aTJEX?rp* zZJ#C7*k&{e8f}9ysrTBRj7!^RA~m)dje0Dtp)gA7ct~|_oM3Y;X8KJkM#x_H3 zXZ0kvwiw;>8|lfo)sMI#Z!M)~YAujqfyoZ5}Q6Jy?T=F~UM@O%{V-hP-u)DR3en{giT2;@3-P#4CJ!7ki z;j{g4&l@$eYn4n#S0h?+)%LQxwTo7@XYB3JD!n^dwkjDK(PC(%SLR&n$}OpHtaIG- z%}`3rRtdg?#qVeDi0V@Yw!gu*WVC0-$n#@5R>^48pfP?^Z?Z~yH2~H31lYZf7yW3@ zjFC5hX{(aaD6o4(78>mVDj9hLm}(@WQDFB-FElXc!#8h%@-A`J4AyseowdWR2DW#J zh*qn*wF^dj z5H}f`o0V22qfyzXg+}I}PM>K$E*P5g+ToIcp7*<@>AFfrqtGgh;rKoJNk++2c`ioT zz23H3#hS8xQqxuoSN6n?l_=P~ju#pj-J!MsP?(S5%?)hKY<<5TgxP-8o*6^;$CVjO zMxzFev#xnI8LM1Z$D7Ri zGzxZ)`eJn3Gh<-o_nW(^Mlu>T^n94jEsa`zYSjtXRj<$mqdjA*ilI?B0b#aElF=xz zd*v?}nzf3nIWJqQXJxgw2XT|3b-dE5WHbtFjp2$$dw@!YMtVgf8I1zFM;bjJ>%*aP zobLv#XwAD}-5L0~ZI13(A8z6aM$BNHAKMJCN=C9xjj`I>!~=~+!S3~TkYN-f*`~&% zTIlG>xUe-()sJn4QPi+ajj`I>#FKFcyLX?1j6x|=GsgOG6Hms4jh^#vSN+{y4o z*^jZ>+r*P`VPkIguH3TCFp80EQ)5z1cl2aj*jR~s*Gb)G7)1@+lz66Vx3R|W=*hUS z`D0I#``%!-jX`7+8vx=l!Ta2;V+r%^WqfTm#ZtW%8 z45JvyHpgnL_BQcAqfyl-Ju@6+Xf3eTjL<3P>R%yvD(|jlW}2V6nMj_erz+0VkFz_$5`!c;>ozMF*m$3l*Ts0C`PhP zjY(Dc(UWmuV^t2%B?lQsQNuO~lRCnqC*#8I=aPdAqlOU~>K9RC`&2U{PdGBhn@o;L zww*SBd>dN-O&R#8JadNh>b=i4!>C{ne_N#QiS&3?%kGtEZ8mFL1MFtxy4q$KMZH`l zQ%3GlK=A~qJb!wvN(S_X_YVjAVN{ODvgeAsCrT}3#rLN_gLTS~fw|cu{_yvGCiCGQ zCMxu5r=E_L=Ac@o*(}?Umi@4Yag(7@V9O57xlv?$M3xL?XN?a~^~^zrwU-Qg6t@}B z8=m0+nD#swMyXF+mFUOA@BH!0JD>MAFYp%q4k8fY8h%%mA+`Ya?!`AAJAU(hcOUcf zDI+}td%@Tp9o_%l)63U?ZKf5#V=saKXWY^ zVeg)N&d1KKz2u{J4RfB1^lUJofpv7s>ce>J{BSbDw#J7CjTJ_DHW*_+Zb0m&P|2X} zu{xXdqZn#?d4ipcaX!$Om)=Z9*q(D~Xg-ReIVjHt0~%T-VBC8%8DV?vN+TIsOXb;M zKtrn?8b>#i5w>$s8p%*jlxKqh4P`Af9)CC)VS6u;MlzJ!<=J3BL;DqG@bPQO2z!UQ R?tN^^NY9cn>|IAk{}F_M zXr61_xfcilB_bN{oHOW?n8XdY1QImn#qGJoCCHOcGYHAK<>-~Su40k=0JiK6~<=)c{A2fP(eJnY7F*Et_mS>9>+Q(orZ=U@7G zwHU#gW(1?3x?@g&nB_ST!B&jUCSBiK%wZbiFvOBuz8N=jNIwu^R>r~oYwZUktmlYe z*&{NF)i8=xJGGSpA~h@f{kgTj5snrFYuE}A#^=0J#4OK&2<>^wg+2Ek7I`Hc*cMvx@5NrBrU~KWW?tnS))pg7 z=KeKDH}AP=nh>%59&!wuJ173uNpHB-dCiJj;%$e#<>af5xHg`0$m@R9@(2pYR~Fo# zo_)bGrx|np{PYjwdYwGwushQ0zqOI;rO95qBt{PebmpFQE?V9X^}h(Ig)-DL*bYx7l$8bmxi^x@v|H(VWX z$T~*^T0OMo7U^~G%?l9X6|QGo!8A^vBQqePe4S%kXjQ(VP=g3s1*v7ea6Ax!R=AoC zAw9?0fU|^W&(S~sTS2T)gNW$lu6RZKX@HRNKm=OxeA{-!`qkDk4>Zv3mG`U{cP#4r z83?rESvh!op8^DG5V8N}dv~4q(4fyipcT)`Eq_tu6>1Pca&Iw56T(~ZJf5&*lLD_$ zgY8nE(&AVl0brpjFX2mzjtf zMBv)A_0ftzE6gz=V*kYpG*klS9ObZ){bc`~1E!BkWwl z@{0antWW!&x$gH6ff_{E`e$@G0<8{x;*aT0Prg>bfmU_`;C9Oqs6m8fpH{CBfmV;b zbYr^54x3h65mB^s_PE=(cN*Jk+3Km^Zx>(xi-83Q)F8r61Fam0Kr8YpF81n~S3gY8 zdH=U=oPT=AuhXqI{ewrC!wHjnA|Ui&@l2Wk+p`kzbEBPL%_(DOS_dNiFlwZmy_MKRxr z%brfZIev5j0yT)hnIC$E2(-HUu_0}*J2>oMd&4I=EM z*2;khw6fDOBBbZII)hbPI(KnaBVxhUXQU5ay`@_>VLuRoR=93L1g=z?WA1*&z89@p z=?7{MVK=?jo+ARSXkV$8?l@k92-+pwjkT2n+d?Z^QB~XR!k(iB5wsrN4Y`#A5okrL zxmvu=am=#~pGmJc@+y~cFoTC)p#~AP{Z^*4J1;B9SBMC#ZtqjSbRTN6PH$_hP=kmwK6p9(+tJ4qa3BJ$Fjt1LLJcDR)PH6A=8@wH zI1qtWn88C1+5z0t0q!B~C9&-#goumx4?2bUlNat$cv3SC$ycaB1n!T9kTr-1w4(JN z7w?0pK?G%qxHOmew$O^^bXwwA0JD2^i7Dcag&+E6mi=NcarvJv3(Tlt0 z^*fyYe|ZXW97X@wV9$jAKZ-hfPy=$xNcrE(({cn_flM6i5qm~Yg?mr~GPOI_dCVS` zBSI^W5RQg$^z8vF(s(QGM{nK_@~RMlRv=SL6sJsLbtn1i+loQv==Re8c9AYepcTl( zL4C+%1fzD;fK2^Z-m4>x>b_PhXr8bqkKaVrNR&`QUtfCDv%&`1|>AR@FH%WJ%V19!_-#Nh=Th!9zM6?laR zv{IQo=2%_6>Xh0mKf5rYH!bKS)8^vy$h`keaXd`s-=k>5+jdB{s~kj#wjR`&%Oqak%z-mMipmgZWwLPadnNYX5^78a4vp1kAe@z=dxL(^ zJ~(zLYD|V$r7Zh?v>>$S&dTIqJhEu){q3kRncLN|Q4Sr!76e+EEF3yZ=*-Z+f*O;> z_dL)0dDViD-N$wrL3oY^%|t@*u7jGqUE+g%ki05Hpq0r!RvFD*;%MW3xVBhhvW^Gr z=M<|#1Vz_dnJgSM6Em8-G=fnDH6}9$jlVx}xG^t8pq0tOK{Jsf>)sj-8DflOa}`;k4&12<^GEGFdn@x(UtQZq%5}96C12QHDS(lZ8WPNfJeU zIbXS~&l;1N1NRa)cX?j5AVRA)pDX=rCq$S<5kY)i#XHUkd(4hMIr`Trdqq8Wrx*2* z5$^YJH^B9A!A9?P&HC>9&Pq875U4@KK0_zQjpWatfj}$tHuOp(>e?cXUh@jQ4H2jb z5$AOO@aO+q;1wdGD7V5sg&aDUTwCOOYLP~7Lj-CNK~YFcW94%RT7`YWw+(Hj@;HC( z@;A~)Zr$B^h~9=?p#~8TKmJ7e+qqX4#0n8;g?%y(Iq54R2CtlKYo32MgxsT0qh2}0 zu}^=L?zrrGnoIB=g$T65h!k?TJrxlu>t0*Hfe0sK+(Hf=bLYFp$H^Fx5P=#*Xrvvw z9D!CCH$&LXYpl;QI+t9#=&d1SJWzuOos|V%Ap)(iPc0lSlksfOb*Js--i8RvgRO`* zUgrf~A%f4PW`%tUIcPjMbGo+3ch0Czrv7mu{W0$U| znAW*#7rhO=LJiFfkDwV7(>gEk3K3|9eF`~Lld@NeaI&`KIQ!Xi9=e{kp(w1D*3ptzy5h{N^gtNl2iJ~h<&8aRMylZmwu`!(j zmd>8u*sc2f+j{81&tak9CJ_#dGgNSgJ{Hg?jRuli@_4w}1zn~nydVIYk`NwND=0FW1a8^dq zB0`KUK%mutPy1AlI&E3ZF^rZy+Ao`J$86< z-r9D@ff_`FvxE`fFF>Hx=!u5I>BuSv&k~wfjsrD_ zz&z&XRSN>GbcWWYAG|&eS=1+kx$88D(6yqmS|sbE1%Xz&(v;>DAY)euzV$1`)dE zmE%%EtT%W_#<>I$Xr=34Ii^td`OV;69Rf9opd1Bf>MJB)wID*Po4P5FDaYhdbLy1g zTtA`+HF>+l2d93@i4Gw-F-M>kd7DyBR1V6C4a$k;mDeDG;s&R1%83raBZzIG6~!>6 zoTwZ$<_*e;HXdGs2pWHXPlzJQiG>KXqIs24PE-!ciJ8q^)F6W9F`V0Jwr7+R-P}b4 zTG1+~Q%=m+U`9F7X1muQg4UzISws=##6kpG(Q2+!PE-!c3>oD_$AKC|P+sAazUC`N zP)=+?pcUn-I^{&oSCrwhDB56{<}0s3gvxH;jUqvOQYk?=E9KC~ms9Ing0dg9sfP<)B?Hqny}+Kr0<{<=|Ojdo5}Zp>s?*bY3|QM4*+< zx2n&H4a$iL#|kxw(6wS5vOZc6Xr*gVIVdMKC?`4uY7n7oUO6ZyHYg`1niF}|y0*|t z*S~U5POMW-bO_WS0&f;kL^+Z3RSP1t%FlLDL^;u&`Z!j2>O%za@$(t&$Do-vHdeQ{ zXOA4!nPFZ!ZTfZTgjt)_CokH&ZtoGY97Us^zr4}s?2hcVXtw}?R+#zdoVY4$?0fE@ z?EJkuGi(?6?CnP3nB4J)##e`Jo9*7QTZS4$U{;EvA6@ac#t(bGlwELqXMjMfqc?pv z-Q%OTQ{gzc{)Oy_$3JPTKdLiB4I=1G9`~NLAU1ku^Q^LHZR6{ccgs+Nh%hJK^_RZc zd!zo`xMxCVfIzETA6&1#eZTwFtMPNU&sKitfyO4oJ2TWE!rtB!ug0BT$?llHu(9Ap z%3JzgA8QbSxiX5rKW13=r9WTO7pO$WMqaKM1*;_&-tUXr7!%Y{*5y`0|Z+2nX+Ad>ZdpM3dh1% z_RQ{mer|eN|IQ3Gh_Ltl1kv{IeJHozS()~Skr`?bp|WP`o)w+hKe{fj{^_jFB80P2 z?k?dN@xZ98I$-Z3LYL5i7L*Ll7TK8k${m=PzqhMs{SVL4?jR z_3FoGZk-)9?YFhBo!1#4&`RgDdNpdJO|#oCeYf`9hofz_I}IY}-C%uLdoDwsGWt_fIZ+eY9l;r$L0h zDX$~A=d+DdW^SE){KrulY7l|@N)!!xd46N@>K&4q=XVAOw9;Hz6^wBw)prs^wL z`}W9Cg9wVcs}hoaP;_e+T|}T&=+*A0Z=6iL_k-HLKShtAz& z@7_GQ{a+u{-ksRNE6Qu^4Selfaf`~vX{attG+nKrSb#~Q1r_uDk-|BEkX_pKey`v3P&@Fc3<3{TytlmamoQBY<;+XAi~~5 zmsrs`F|l)E(3ZY?&Q>@VqDZr7#=C*8S{EP9c23p|R~L?j|2nI7^Qn7h;}5Oy{=pg9 zX{>sHt*|B9IcMHjgBuHHYS%6zG&3m2o|3OJ$n6e+Rydkbbji+7*0w!%Xm(uBFw46w z2&+Aie$f4+X7>+l3$1W2(5`gc35~6X?Uo%st~0~C6GegdSLZv$%|COBqGKP~pt0Zl zJ+e!_PIm*)Aj0ar#H%wmT~eQWdRMmW&0PaTXmuw%Rr})2d)4nbb>Oz(aLf11!=5O)!EEY{#9F>t;WZ zq6QImFA=YPHR-6V?~z|3j*f0bpq0tu)h_Ryntf%**XRwQ8TX*ZWNw!-9N&c1tDY-Q z&-Qv_Wo^tqKTJ`B2)o0HS1(UJH+$#3dCV~s5ol$yc(vKb7iKfpe47waJ8Dekc4?2| zo3Nf_Mtg(RF(^AYMKE!PM-A#`X=a%}}o#0>wuM$Ei&x+4w^7!6!Ep|O8k4zQ&3wA!JbB8RMzZyU?54lg0u3T; zM-{Jrb?J+ZB@51Q9M~3GnJiw-SaoaTrj_3(#Fz?dOy+iR-{qw`t#RFg$=UkH?Hgzi zVY{e!_00NRjmH=Lz-Zrgfg!I=9m{ zbI=OrySiIKm59OYzwXIckznyZen?ta;;UYhBt`3s+D?9c{h=~ zOL-JDl!N{K(|#8Y%Dai=-K9fKpjUeVbn zk+aY80AXnG%JnIV=$x3?Ig!qW_N5tHQH}$>rCc)Us6@_*Z9S;bnGqnwD>^48a!!l_ zgrV6A`xHfVrcUfkP3LI)j*mSla2)7u6w#SFku!Bi4{CHp1qktq&eVyVsrv>9L$ek3 zDT?U+QM3C8-8t+FM!bvqr<~}myMNT={?XBcnj(aFMfZUWqZGZ3OGhz_a}!aG@x&>XBS(e18gw>w0j6-LC}AZv1i9K$zA zAFCpS^qlU4HMtMA1qeg46~>LS8ttiE7cP5xn|rd&`N|M3cTw#L8Fq^-2!5-7hW~2@ zYbd(*6(EXFE5bN(4I+rozT!jZ(5oB~TIJq`2+AM+bWf|+zBKkZy+Q=7uDX65W*uIk z70rD6x>yr}b~5{7mOrbPMYlCpw3pbIRGMxqWwD~%Zr??zV?@GO**S_mp;Lx^)8})> z3K6u|+E>7udXBRJt%8UIV{ZGldgV_}*izUJ)Yxf>(RTKcNSDP5tuP`XhwYZGEjSGz zcZdiyfUr}|y1haxj7Z2~I{>$3dz7@BubU8oULnHv-F16~RzXCFB+n(7KP>N-c_q07 zy+VZTCF}MItuP{C&#AJ>s!3z5uHZVa7^+X>5P=#*(A(c!?Z!1&>p-9tRM9peP=g4o zLulndL}IxvxNOXD|>IAeJ@9#1`#UvGCJfaKsYPyUjYI& z*sgk;wsIf>tu*Qd9H>ErM!J9l5uw!#o{0q<6mzc$5fgZh6>uPevxHgEf4RoJfFso8 z2;y^9X|1tB1X@Y^?rRH8BZwMAP~12(6!ZfTXvJ|Vo{6YI1dYE{%Qkt12((hUOL~qK zptiQ@Ezel{5wn%a{JX1I=c->yb8KE9JbU6a8OcoBTmPL)p%n|mZ41rcA3kSuS zo=OCD!u)n@(5@oHLIhfw>|@2>XK>a1s4-c`!_{W7?7z>@f}rSnE0cwTMv%YHKx003C~8dRc4=f? zZI*D9A<)WX;h^}?4ORYK8Pu2z9Jf-MNNGFdoumJnhf*SK4~BhOtYi|=hb-;|>aVfhgep2Jtg zo0Vwtc8QO79Ob|hGE_eJbk&B`1BFOT2rz83(lh7KH+@upfwkxBQ#DLIhf2pTZLvj)x-L7-&lcjgEsQQ|5J78& z>$U?989_v#6-M1S{EFgHi+R+P!^t$K*<0P!FjlBR1kGcvss0QET4_tgtJcQ~5h{N^ zgtNl9S)tOvT zW$(i|4I+q->p9gct>@&*umFKp^nRk%e-Ve)b2MuX4wBzV^%_Lbs^jb?ur0LGaZ(Pg=X40vAVTMua_GEjL7`e4Xgz1f?@*Gav%3;GJ9Qht_jC1Zoh$`@HS#zMiuM5n9c%w{eL> z>p5LNco)^`chcnT5+9so^t&I90}*HiZ{t!+`rQxn%HFNzEb7~(xcRddam#l0JH8iQMFfq%Kijz)_d*0(!F$%kq2K**GZ8h2pm_{uADX-T-H#Ro zTG1-tN}GHQ@^?RMwtEdCXg&JVnX7RxM4%O|O|Di^4$2Jt-4Dls8bnZDu`kd_PUP=? zv>?z*YaKLSQHGBGVcV<8YTIm{84*l+jL!br`y5^Nb zzx$DBPPCdh%M8v+*S~V;cRw5gHDSAvKV`a{=qlFrL}oR7w4Tw**ZI-!`rQxL4?OiD zg7|v1#+}v&RE#8;m*CyOs{PfP-q9cqs&TJrjeCGVE6jY96IW$5t#MDVUF5UBA`1uA zxYxACJwXj3Fps$!cdIc85NHMO-%&rP#y!y*_XIVFu)lMQS5)JkXpMV<8bpLS5o(tL z1X{s6cjOh-xF=fUo}dO1_V%85MK$h;*0?9AK?LSXSL1HAO929{;GH}2ifY^wt#MCK zg9!VJyLd%4?upj8C#XS0n0KKjEt8q_Ig9x2t>J`*l1_-o*ckak5s&P-W z#@%MS^9m96{)Bi%HSUSlxF@JVgsw-;yHLX$AkYflxg)Qr#=WLB?v@#xSBS9pKy(E6 ze72@F?g?rTf%}T9akm=Y0D)HUJ{);PHSRU7aknhW@9$L+VehtxS5)I((;D{#HHg5S z$kn)86?T9?D|p9`yrLTSs@AwCs6j-y6H$%3Rjdby(8|B7NE}o}XI1gEdQp?_eZ<6hSq_W*%bZ-M#@4 za3F%#ht(je9~l z%0DlmEb5%8xxMy19o@jh}`PQJlO<7jHR5+-{ zJ<}R@-aoj9PD6XUdzX`~uq9XHZr`j4I1r&x?-dTJanGnCWf;{W2MDyn(WJtMr{YX& z+znwnGLNQfm-c!0&aH63H){d}TH#!9HSU?#xLb5xd~_AnIaWH4HC9yPo@tFc?;pH! zoQBSf_Qj;Cj;w3R)wtWYkOB@w=m;tY)wpL`;~pT;3P;n`xYIXlT#dWUM8}Q@dzV*Y z1>Zsn5NL&S!Dmsfako|L;-mS|$(rHn!a+6e4XttK-N355`Oe|q_+=~2B@XRwEcR8d zfCCYl8I*%++&N!yjeCGVD;!N%n%Kj0f%0RpXXF3>)9+zBL{YFRD&BGYGbdN$Zk67=e|QZd?0sSJifY`eTH_udLMwcBMm6qLt#PNFGuJdD zw8ot>obJwC;~pRwZB{t`uExEtHSV?#>e%K8d)Ha|0oDBh0Ty_OR@^RSBChjOub_4*MhznDULsy$ z?Ghr;%4G4XsCJ1pX2tDNhU1Dl^$O~|V$>kQ?r`E2)_EZUtxOiLit4;rV^-WQ?NMBV z=Wdn}*2D!GMA&^-yuz9|YzwVS7O#qG;#gx=;Fa#@P(Ns1*^X?rgjIVsAYNhppnByH zXl1f^Ra8I78nfbdHR`%^Lak+>L4-X=5wEb;GH5HWo2VK>yeg`-bQ(bD3{|h7_SM#b zXaHf)oWv`veZ{uW%4G41YTW4=0N1#W@wKn4F)MCYSF?IWHSUSlxCa_U*z-B@3Tt1n zEwnOOyrLTSL~7g@`)XO%m=(9HnNRm~s&TJrjeDR$gzc!}6;?=NTWDpnctthtHK}p$ z?<=HPV^-WQ?z^tWy{0wpfd&z_i;7oRA&qUJmC522)t^_T{yeX7XN_4&yZJ6krwsaL z)L{=y&kng{KiW-l4I)UkN_MizYur2Nz1INYtqdVvQH^^;YTSqW?*XtUG#*xWR*y$L$8TAnrU)S%RO6mWjeCdxmIaT8 zq1g(@#?`oITH_vQ5J9Wi-(*~kyZ@F2wuM&qyLbiP7UAq{6@cMA6C&bj-2JyjFjka< z{r%H^7mlKDi?}tR?Xnfd&DFTucUX8Qv+7LVulx-Xy>&J2{yQwFDME->Mc-jzuMEvr zL7#X(w{O<)u5Wds=9Sy^(OXyJ?!Q@s8ucnbh*z|qw|ujPy)ragVV_)$yM5m$rt^-~ zpPKJ6BhXt{&J2{<~4A(G?XS#H*t3MzL3h zW-IKIyMNd>wqkqg$Oz4%?k0rZhTqsiO%X!8D*DD2a~PVfuuoydy6%H|CkvnTYK=SP zM68PE=f=4vM`#Y#mf#C!R9lxL&X z|AX`67q>h$ed>-mRgzPX-S6B|F@iNs2!|HL_#aQn*1v%M<%Q_|_9hPB?*5Ax#v2_x zHC;CXtxRTbqbNNy$$tCk&UCVDtDweYZg=%Rm&8X*zCt<55NKtxa7?{%abxYwvx#GD z1vMr+j-E&3u`kV3j#30ztyWn$mf!qI_2$i{5y!?A)R@d1*@n-=R~&hja+D#^%4Fd< zzGKVe;$hz)j-GbZn9Llt{Z_`aJ132HnK{n*;N|#lM<1gcWeBt~SvX$&$4SY5E_k0R zc>4CB#$@LBQ~#Cmn@5gQjxq#VnJgTSuKjY-wcyBvIZ$IVbDX&B>G+%DM=M7e0V`_&Vd=YVs?Lm#n z%yG?%TjFhpyrmpv2(&U;I3^Fdp|N8&i8wayL5<1Gan%vm##0V?T{+4SXl1f+{MSok zvZVt?5yu(bs4++K!2E0cwTc7sgzk2~8@V={BlUXtc}R2c%TOcoB>)iT`&E2uG`bdM5OvY!Q ziE@(h8br{kCe6=R%ps?xvF+FvTA3_f(TS`sXSjhqs4Pe}9oM;QXGOcoBhv1D?`>03dK$;?6boix8kl_Ai|WZ|HjS0;D0whC%YW)8Zy zrTKlZ41rcA3kTgG>vHEDUO|n?%t80hG{4uDA<)WX;h>vvP43Pc@V(Zx#Tt_x$3K^( z`Te{U0akSLb_n618+{_r04B7f#$@K8=K*Q{oS_VXRwfGvJPTvlll!jZS1yJDxvGc2*~Mr7Pl3^&VA*h|o%9ImsNd;X&DJkL|!G z5AHUT2;6D2HNAylNYE0&K_uqW)-V+}hq#R`k zv@%&Z@MMV^la-?@=U4~ATM^pHz8^K|M@J88OlA)1Q=G?&`ca5LE0cwTqMOKg^zA{7 z$!-iz?uzpAeXkI z#$@Jr;nXv_mY;E%a+D#^%4Ff#Ouj-(9DOUOF_}3getO%(&z^9xa+D#^%4FgA-L(%i z_CA512)9*GV={9*JoMq-@i$zp9AyZ!GFdoIyFJOi`zSxz?pr~P$;|Q4mRqFPy*E!e z$`EK}vT)4)$&_rjFUu2p)R@d1G{;h#mGm!*lpxT`AwWUK*W3u(*qJC?%AIi~! zV6V)|WZ^i2Vm0y6ofBRks4>~bW5SY6sw~rUl@bI;*Q`tyj{l-D-{*w0iDN}KYE0&K zdHlEhMPKD8L!gz(!qHB1cZB=qaz_tpOlA(A$AicBQI0YMTA3^y_tP5O;@)piKRS9) zV={B_dfaxz`pQv;Kr54lqei)8%=_Pgg{&-O9|^~+l^ALm_eiF0Sp!J}qbhNGKjwHzHHuw6uO-159D z90OfH5P??ZUNx_~Jb!#1uXsfnf@gl7;jriE65F-f8($ zsh{osL{{{iK@t9mg>lG9hT8HPd(OZJdmexs;+5S@Sz|Xy<0$ruIZT5HyBi`$?v)|X zs=Vi@L4@56kwf|sAmE;9H$6m%SE#`o9m($R+^q8HsA9K_o!k%li zav%b&_;-t8>zJDc5%yf8n8Ofgg>xa~ptDA^&@VMm5c|* zoyNw!U%>6+IE7xJ1`#w%+?xZfULgXl*ei=j$blL}(5!TC4zzLv2(ZHSA97$epz&~j zW#@LWr4WG{M9}!Vzn`z$E41R4n#UtwQKmrz&13iX^I{G|pcT#q?nnODC1Uq0$K+k- zeAM)`77>^e5n=scbjZu1c7O}f5!{-uvs-yg9{mE}cOuXbKdJnY7le~+SOglQ1LGXKtK zx(glaZg!Pp-r6F&ckVfL*4(s7-x|xz!7_2D{QGljf766OO*4Ygg1`}E1Zyl-W`*c* z1o?izRu8?lN9~JSEbnD`_(3(6yG#xd*xRDGy|VF6?$no$xgl7C2$R{{kOSEfz5I~B zx^cSyvF)2UK0IP)r}^iLLuzkVmpR`L9adRKKd`MLj?Ipf(`()jL$C%B<^4beS{?A} zV&`pZ&#@mEg}?mIc!zi)-La|XID*?8xX;5pYCjt=G8oO4==yO+#IxJ(<$j<0z|Kt^ zI5W_SBJB_y>5v0woXI_(Zsle>d)V4@ice}9L{JRf@2%s32(+T;`j$ekaAr_H+$`bV zVx&U^Y7jwj+s7hZjtH&tl@=l}iZuStcb>->^$>v?M9?g8=+;?+2(;SuybBy+r<5HV;XZAOqY!$98bnb4+#KVKT8=;~>XYMWjTLGTLH%$D-*f*jFS3Sr7VaTu9F}!w z@Urs?5pFMH1jmOF+%CtEWnRG{0yT)>k!6JMx#!^d${Nko&Pp?N3BovXp9OJ|5kr95?dJeSWJkM6TQ+Ki48eN_l zxh6+&CgR_DX9!0S5opEPjuC!0@Lo}GW7gPdiDf)3wf5W)tl^#05GMOGLkkBY*ova= zxC_U_Yp`8Iw5|`%yX**4@C#h0*mIL{QuwW^{9O$5e0xL#upj!tubk^L}L> z;y8r})F6W9n~Mmqv~mPmaqeQi)|rS=#OQKXVua6Eegsj22=q4e3K3|<*_Anb-t`=) zK}2~!5P?>l^O?i%gPw!;LDS$$rIy_9g5s=@~-(;5EVh;H-vxxK^U58NnRQh-Ryz&St`EeP_85b|&E zm=(`zlZ}tLEw_gV(-a|O?r!hq)r88hhYrm+`!GANHA8T_n3bZa8NnRQ2u2$>y{G@= z2paQf&b5nb0SC5=S*aX>RxGo(l6`u*=hdPazwCME$LD6KK}4A0$`EM9GIK~yoV?XZ zb*fwHUi%=oTW-isgJf zXv_(*;T#@w)F6V!-*NElabsSHKr5D+Ll86*3Gs0c&s~~vDQoN=Wmfz<&rmE6oLIhf|%pMAYG6OyF8{5OV1T~1Dyy7@~_9;Z570b*a z2+D9gpV~Pmq6QI^A03C!qJ;>wVwpJvLAgDnf8U|Pxg9l#2+we32()6EIpowwJB}Mc v-lJ$|aT?v1ycPeR?>Nl}(_p*E$0wQm%wQb4zj{97ke#y`!5n1>*`5CnTXs({ literal 0 HcmV?d00001 diff --git a/src/wroboarm_23/meshes/forearm_link.STL b/src/wroboarm_23/meshes/forearm_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..c9155a2e7e187307b18584d1c120853e14ed8d02 GIT binary patch literal 19984 zcmb_kYm8o16}=G98Yr4Vs;D5Sov9B*(zI&6Z|05<%jiO=| z@d3(9D3U>xYs^sox9F=&mC%FlS%j7z1LoQ z@AJIp-aA$G|NZyH-Ky%`6Ruj^|05r*tLnhn6)-@NOw5Go7y1x%qqlovP_SoqB~&U?`j&3E2?VEy@j+&EB# zS{=Ff?h7~naC1aFcJMLHQLkQMQ5`a=8lt;V)!#X}xq7ertj>>3&^v+ zL#P$yz;V;Fk8ZBnxU#9LNlT_kqpwhaVd#LaorpntiT}h?OT#Hy=3YWfs*LbE+Y_8`av&UeK(5 z$(s$ad5%_ymogAjr_7FyJ^vMvqYt50lw;;=f4TU!Q%*CEEpw`&434`ldD-Z|zwH=6 zuBtpFYZca6ngWuoI9(>le$kB(WDzyr7;+PH`TjyvMG%dpT zhHW0kQADT}wmqy?MTAv1Sy2ug)`GRS`QB%vJ=_W!%HXi} zAENJuy7eK{igMtvo>+&TxE}o~`LbR)WPj!LfUw?POK*1sG>WjEKh=(p7e4Fg`has* zHoINCd8oeB%0|}|#(Chl^UUMwwclH2z2tzok`=Pe5jHc_VJ;bMQw?PxY+jja=c_)1 zT2T&B*$h{QIdRjqs-X-Hn;)mzdAARtR+IyW&D3?6+rKrT8p`0Xd48&0Kl%`AMLBTT zic^O*YW1XQD1*b+t0}CtkgKW>p;nXwhpn7-SUHcKqz1mwnp|IbJs@m#u4Q$0c4!oV zKGv@1C;VonUVZ%P`dwFCfE_?WsFm#ohV8!OmW$Ta3umpVtLhVzB`ZXjBWx#A`%b31 z0Q-{Ui!ul&*(>}MiJJ>hULDi2({Ajm}jmUMQ{v; zQLA~_SWEXZHU<|s1|f4s%{idqDh!$HIXqDYVw0`2Gd9+@&srX-XHZ^t<{Ps+y)J@v zA4ecUpqEC_3TWokLHMkH-M;G=%*yvADqAk2E&^APB@w77WXt!(_Wz)Zpk^EaFU35P zFCt>CjC1{9V$BZ<9A-HW=7>OqBgkew4^%fQYQ_=FZKbIO2vimkFO8s8KzlE=kvAR{#)0`ty`9zNSScge`|=2v;vmAJ8JJIuf8^HF+o{pm zA;+BHVXV4}pjAN2_^{pB%qp9GR@odi1;l|XPhEhFY$@Zq{e<@DAfOpXWOGS|ut=

XENKv~khazYdIpY1`cvSF@ zc`)P={6dCri@3~@5VQh<>q<8&YSeG!!{{n-D8lk^D26ttP~L|8^(FoOB6vXLC<$NqTkqe!+f>tQN`*y+WH38!2*XyMXSiM z3*$o(u~(KkWJHCPA!hDl6PdSn6S&VnRP4Jdv-bcovufh}k2e#y9pfuKtt?A#G5oHc zfT$8eHHwhTebkl_Y8B-)1~I!~)!F7}85Tv#Jj%Y-@;ZWQ5fX{da0P@%wcR+bp9Bxt zVJT6Kq9?BeI9h~i3J8z36BVwyFGKjw5`5;#uUos@$?;eoNuvnLnCG7w0V_sZG5F9xIc@z+d&!e@q!I ze>S0hId@^FPdP^*Lu%0TDf2q_ySOh19I8X$hb@wtmG8=k)6X9W(8SFLazC(z|Qs8Iy?PX5{LPk~S?2Bl@+dyvG!yN*YC2grnZf6GE-PQLe69fkWD(2cfWi3Hs9NK6C$^2dw$-p%x`Kb^xbuvAM{qUsCJ>3C<0F)-g?$Ug*MN9wN}WS{Vk6w z*R%-a#0dKlYK6M7zX36`%4RRWR|5y?j#-8>dY{QdUhg21ri5VMZO<~`iy2ameA!%* zBiKjB5j=-SRQ(8A0S!-S7PZwdJnb`$_i9@Od>@T$qwEOC;Arp9>8pew+7VXWbeD>| zA5<9kQGO=`8Qi>{BUDpBpz>q)YS9Y*h9WD6tyP6KUkc$I?HK?gK^27q=M3(J)ol@~ zQH10dqvBbHBGf9%>71cG*@j;^BlG(YMrdu6?hSGTdjrsrM-=8CYKu;VLd zo)EM`9_(*j4r*fN?l)$R2=V(^FHuB{%3BlG_`QpWHE}C#8(79D$2h1#B#JP(XAF)Z z+$!X>L{uJc!0pE75%#jeZ0vh9{xG(W~!&l_+Ub!@azQz$& zg?7|tc_@Nbac$?p9Y3v=TI0w>v((ePM-4qkSOv_Y!Kx5#;W2 zD1uf%TW&rdcM;UUN)fRNo=0}>lh#y?U1pyGLOC=-UPn~fi5J#Xk5^*{henkns8IxD zUI#^X4wrnXRmh`VadL!NqBr>LL%)Hq?Il}yI*3yo^rwV~GEQ;G4PAa_nKbGba^!PF zc9NPQXcf5I)gVX2>iQTYBJe39o(|#^hwYJ#T3ko`%qu$)P8#(KSrOT}PlljXA zxRxU<57(&Q$d?e=`4#d=2+H6v|MRE{IC2Cv>K8Jv1F-4Zcsl59PK{cHJi?scMVRHh zU1h)WNCIDr*v`{IzaLNpWyu5H>^@4)ESaJC#%$2xbHoEUb>>NGhKM1hdAptnvpr%|!3udG{urg@A!o=*qkbWCUh&M+{h;0B_`PM^izJzE(DFX2J@HbF z`ArDOyvNNs>|OBmEs4FeoxWYMcdO-F89h})hTKO%=KjjwHuf)(x>2b{5z3uMr3kgM zx3T3bA&p8kis;Y7-n#cMTo7;JZZhp&+v@VW2_Wp7hV;z`S`ceuH*?h}!oF6JuTnG* zMW~fVo7W1xgzWs10Fj{0c|Av{MiKfAML$BVG};a#)kG2cEl58iw`#vo=_1&x5eaqx z$lOMOe|Ohy57j6F?N79G*d1Fq_u+e}c>kO4y+Y<2wB7f@nJqM|E@bxUEWGe3!e+p&CW-z2_pr-_3@GZ(Tz+ zw7+}aMQ~<-hOzssQrwbK5Ub7*y|>Op^R z9)7i*azw6a5q$5x8!K$rvp1HP~B5XYR zD$(Uogj!kK_{z{ls74Xig1#Db5!UAE3m&fRu+pmMd8kGae7C;Kp$N6I>;A1w7ooEZ zzrli)_Ru^k)hL2rS9LiQp;ny1y9m`NLTi{ur3kgMD)@IgT@KYKLTl(8X%ENQ8EcX4 zebPIkM0eLH)hGfo_g(!Qie@`?IaH$v)@^BoTCp_);^AA~G`+Cj276X?wS6PiK0m`V zFFbvF?N#5Hq8v_G?s?5V^(*f_))1eZQw?Px@VpJr2O(EgA407t2adz;KDNI5HTxLH z#GGm>J$^e4)JqYt50lmo}&ejDmv-14Tysyb+!YAC}mpAQF)K7?9PZaH>Xg{$hO z3Dr<$9(X?7a+DB=idK{Z$2zOk9o8mQwSH1Hl;Ib3!}Gzw(T7kg%7No{^ZzR2sqEW6 z)li0Cv_GC&297?2T2T%hu_qeGwUer$9Q-c&)7K#PA*xEP+UKfOWr#)V?Z&ai-ZE89 zi!eTa`kFY32(_Y|YSnnHwtpIVq$jzQ;n(Ws&uasR)vAb4E6Srd8FJ<_( z_V@P=0*AGE5usL;1BdnYCiKMB6RM#Mzt)fa?S#P5hfpiZEk_uGH*Hf5W#)l56*2))JiLo zBl5ay3$_)>5gOH43rbI1s#ff;T9KT?V)r+*(6$!4tjN0(l_HEo_6&Vdsa0MPML@&e z0L1^?uMz?gvWMoGYjxF1D^gXzzU7d5_Fsdhnt9)x?$0S>7sh+_up{e3s1@a~-`#l6 zhw6)`Z?>JxAGfK7GW_x+ByjX0)QWQ8IO8Yh)jRi`w%y!86RM#MzdR2J9DNA2q8vE( zyz``bas6LxxAgK!)li0Co-+iFK7?9P4jel#dtUv`H^0Sp0GlUOLm7T~7alnJ5Nbs^ zaNIR~&-Cg?&oPdzld7Q{{OVWneF**DUC#rm$`FgrvFU2t$+Y+ViZDL;D!vb)R+Lk% znoz5AkViVjp^QANZu0j4tX4&YT2W4I-h?*a1MT6yprH&7Yk&DG1=i+8gj!J!9M%(? z*mq}DLm3>_kL9l|^dZ!Wa^SEL)r2v)-<)bFgTuz7{MCp)gj!J!95ypFK9|^?mue`3 RgZH(NefB9L)QWQ8_%EQwxv>BM literal 0 HcmV?d00001 diff --git a/src/wroboarm_23/meshes/turntable_link.STL b/src/wroboarm_23/meshes/turntable_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..80b5b6157f38de8ee08be02a2c3c2267211981ac GIT binary patch literal 53584 zcmb`QdAJ=_neI18;}8Y`2hgU0S|Bb}?QKr5oO$|w*;M44`ba@V_R|7yQgYgds!F3*E}?(hA5 z?^>%?t*X8DKDAq||G)oiyN2qGwDYRNg9kmgXy}Tmr)Hmh%}dJ^-}(Dfv)_E^(HK9w z_i5SW&nK6q#FXXxWGfDOGO8~7{C3&wwH8f?zI5LF?9MxOnn;Q8%IFK<%~jWJaQE&W zi%yA6?`>yKd~Ew6)pfu3?J_%?HE+K@t-@Wz#cw}8`^bXLW2>N34>DC^{i!Est+m(f z(<&!WiN0<3le5nqu}&Z2ybtV}opQ`uVm~hUQ7aq$@k_UhSa;}k*|k5|WB0UG-t&L{ zTb3<7c3No^Qo>v1#64e_nVt9OMnla6Dz)nDgE!CKz1~~+&L~>)*xfr8$0pPs zUA*=seLTpht`n*>?c+nQLZA|@Io98UQIu+zb=J$?+`4>s#f*B|b23%pBfsCM=6E=P zN;Kn^dXSOIiO1(|7LR{3fl74!@sR2}Gu{wqxSxX}rZ2g_&k-b}x=t{A(pEWvO7v+P zZkhdIy)X9hAS0C%_5JYU{Lb}u&h~p|R-Eni$DE8joX~MP{P@{@=9LquL?8e6;q2}s z7WE;>Naci%tXi0kl@q8$|MXA$WG{dE)IJ0mshrRm-2eP=0+r|+UVdM8%@+^r<3UC$ zCsZn&<>7(X8{Sho7}t8Cu)^OX&)51(ucA6@bzOqcH8CX^MX8+NO4LlCTJ@eg5o*_5 z)x77Za zN|lJ^v3%f$gFf2Xa{eEq2N`*Iyu-@vvjxBSNc5;DP|1T>9<9N3mJW4}d1`vcGx9*C z_}?$zEt|XI)6t`zK&48=vKSe>{-`OPZT{_`=t0KoDqeW=tZbVFU(Uy>mOv#BVtEV? zzUwz{l@*Q1U=B@beGv<5G|`Qhx(pFJvi zkny^TH~8&2*;j73IC|6*sN_MMd;Iu4Ted&4ayWXB@w$p{IDBz7<@nRO9(4pNc@WEE zcyMgZIqeruTQ_=;@w$q)JLZDy-0{7;V^v3>k_WLoMh3R~_9xn(eCk{A937e;qx@cwNPZ{LlH>?456q?}}Pu zbp$GT5X)m^?3Zuet9{m`18vWEUBwq2yeK>Usq<$x6R1>)IQC=wnKL(NAGgN`q6ZnT zt9Z-D&df&Ut%x42S^||kh~+Une%D4fXS=-Sr07A$>na}m@NwDG=RXrY>IqcxAkIBr zJ9g*Lzx-@L^dRGP6|Y$1@a)j*UhaC-5vb%roR8H`QwJw^`{t*j2N|!cc+D02XVceN z*&VAo0+l?7^M35L_C1q(-E?g9AmeovfA6Y2vKfE9z1xpE0+l?7E;JuiCH6R6}toR8I=$L!zP?S!{R4>Dd?@dm%!CcAp^^!)r7uOm>& zgE)GOJ-7D>ozb1{i02>~udDbiU)?gh?Xl_0nh8|$AQmw)@aBWw)!y`m9Xm%)zj5N` zR}Rar89I5__R=4g;{W}|`Ptvs+A1HbS^||S5zAxw!1AY$Xz#W3rAg1o1C`>jEsoD_ zTkZSNqn<#eO2qPL4cvdr8SPK+b#C+^<8>AP<|ij*3l4nKP&0u_9>gL>uDSY^h3)(A zJ7RawcwNQs>ztIGx5oa_qn<#eO2n~MV-LLhjP@?ySe$vr>ngr`_2aYKf0w@#Zq*W~ zREby~%g6TH;E48)xBMe|kny^T|LMM?vhO~+B=)18KqU`ic?^#~z46ZN;gvJmp7FYh zH~#Kn*=s*`Q}n1OP^l7e?y>ch)!Uz6^r7fM#_KA+b=Cpd9_w|w9(4pNc@WEEWPEh= z!tC28o*q5OcwNOGp0`K#s|SCaAM;uQl{|>$(HcLxwQ%MeUtAbH$ar1F7rnS+_TvNZ ziXQa@DtQp+9`~Gn`sByXIx~8Z@w$qC{^CG(^pVTE9(4pNc@XCwTg`la@?7T34?IF*2UBw%IbG2-v_S^G*)Doyvi8y);Y<&4yo%R<$ z8rNMiURUwAezQh)-9PS(Yx{65fl404ajXVznLM&{_0p%J2N|!c`1*gHlKuU%cJ~@p zN1&1iu{>IXFa2z0=N%8dqvIK`tN3lR-<-|c>iXT92~?^?EMjEf;RD{#`SfuIM-MVy zSMi3&Z9^H}|M)?K6HD zJ?aTmsze+;#=0JvXS^rqFb zQYB*bV|e_Ya0LGx#>+EaSFw)lw39yndJ(*l{|>^ z;}Lq^VXVk_UBzGD`H(o$%>*iW5a)zudYD)7n3M6kiobU7+}^y>G4D&Dk_U10(A*Uf z=Pntqiy!AloV$GqwNNVh0TIur4(A{$ud7&Ns54ltswYr!JbFY}879>i&v;$MnhRPn za*sL!l`0VzMBmj1l{{EuL<|qU5RTrH-Bz(fuT{-H!7O4CBLiWa+F=EX{Xpe}Vm^az zCQzv##5wU)IR75#9&<8YS23S7H4~`hK^%#(u1B1^WV|kZ#V2vKgjy&S{pb+)SWSCE}b2$Gj8fRXpZoysl!tsnATIk_T}l2D%<`y&~gv@zb|D znhCYA``wS&j~>w-t9TBg^16!o#4PuyBTzBwd|PCAuzSp-2P&_tSaU(&ZIMSkfl404 zIZ?Ozppu8?G_8t#>3(;qHBFzy9rD%}CbpQr+A_tr-SfAJ9ZoqR#)}uPoRC`o zZiDy7%#4SAHMIGRcgFbmhac7F!FPzh?C3woe)NdY-s00@VtvB5^ApDvuSbKz!!u5V zR?U=0+A1e1s-k~okMRGBj1yrLqK8JIOiXTfZR~9)yK83fn}{t5-`KfeqJ>K@(uaTUTgKr=mxULIN`^s+$tx^s^z2d_|_xOBp$tt z6G2^b%!4Y9qGm~GRgBf!(7zb>9jhYaL>Tq>x<ICuS4JpNl9%HN#tzWM^ z11-YGu-qyqDym||C==oT6&WXNzEzHg6RxuJzd{5R=YeMUPkjeQEoqtvHztGw+_g!3bgLO2K0^P?CaS5YZlcRk~T z#p!t-Jygq8zIK)S;Tb2aPc!QYSJ_;M#7HOShR2!VoFCzJzArq%jFC1abWVtNLNQ}i zCb&Zup}P!yUr;gM5KKMDREg5vYpEaH^@-r_OtHRM_32}O7LP}{RZgISF5XR)JlK1Y z%J)n7W?kA3GF8HNKgz9g0+ndKA((oQk;)0Z|75?U?BN6|(Y)(RJs5YXxQAEFaY_j? zRf3UjCQykE%9?paMk*&Ry!^GECnCC@0jXxBPzks}QK<@z|ob)wGJ8BB|KXX(p&u zCD^M;`{4vC(W};TC)m+RJ*cI+s1);e2q{6PO0YlEOrR3Y-#4TL8L6D`eV_6yaRQZS z{=OmgAS0C%rCsOJdgTNv(fqwh>On>-Cs_HK2~?slTJ5y#FH61|?=s3gCnJ>;tbC~l z>yij|jTEzvr39HO!G2IPfl4&r{!R%pQaQoZu9-k3ns2eE1R1HEV0BH2;fJ@#SmA!~ zqpjj!42b64eM*p#$_Z6^?*6s<96={giDt(l^&lga6Kj2DYBqYzd-Lxhm*%b$s6=yZ zPd&&;<%CwH{#OGhP>JSRl6v?GCl9V4tgb0RhE_pvoSF$#qP5x;pRtt2ii}iFaGX*P zCs2vzZXhMdNaciPB|Ams^V|tkqB)yW53bu%=~}Cqp*Sd4;SRtFUFZAHU23T=D#cv2 z(^iqG5=VUJFY)ginh8|UIyXfOkL!Q64-no>6!%e5ac=8%d2>%)CdfFUIFu~Ls-8d< z-etsHk<`O8URSR}w_4Y&dsLi>+g|->7T%M`THRfoqOM*Sq1RJ_jQf>6R)+oKplba! z>>;~{*VW#lD&@Nrb%d)FYYcPZnXnHokLSYYES_;9sP)cqG~ctVBV46e9yzi4;>DBl zcszX0;u$BjDK^AprPtMt{0N3)ULweN z-L7AEmPo<=QgANT*KnT4wre#AXH<;yv(^dig@*q>8g~1ag&nULYj?2Qs^TxhdLEu} zBJ8lKAETw+!PplkT*d2LIa3d1oUl0VOuQ>6TWr@GX9gd%89aSI9>-!pI}7~pAFup>bfhF z+`}_Y)c4#8SCw1n{qT$v+Sv}eK4axXSykV2zi#*L6a2i%+eFX9%!o%#vzp_fGu2+N z%tX&PL7dLSeuPwEj>TCL&PV+>{*xaM&v;#*Z)L(f^r;nfb)Lum<*Sc-c*Y6y&~b_X zhOlj1&4KCA4L<^chP+R8)3V^L~W3 ztDSKb4Wkg(L5--*%1S>x<3x9D?_P1-!-=x0t{>iZC;SSRJ22awsHkds?rVvk^Yv$x zXPof+(sHYua8-ES?!v?U`PiZ18}~cRd_L2?8hc@iZ7-{MT^>C`bGMFw7BMn5b;gP9 zsUN>h-^D2i#XJMRy<4p%N56jJXPckg{{F7xrB+o5cJ!jhv;*I?uzmJtmTF(Uc(RS^ z+TP+&?{;zv3isv&KCltHK^3i)&TiBjC;}(62RMc{nUU#B3cGH1p zxA*rQ&eg@Pww#+wpvGRamB>DZ#t%Z?Q{1`dPX#a z;@&fB{=D|JcZ_}D#P;fU-I@@nREb?&wW>8Z^~Mji&*-eCJF=pdVpJ(H>!5eH*Bslt z;~6Iuvm2dz)DfsuiCDz&;APjpoUOR_i0DDa>ndg+zL`KJ58|9yGV6xy_VqszJ@n2* zpP0Bx9=u*AJX0mg9^$l~NTo9r59+ECuS+>RsQ(q=8PQG! zgsz;b#Or0kGgU$!T%E%=muIZjUVXL0OCC-uX8&3q^#m&U5$CO1de^M>H{QQl^dRGP z75nPb8m}Wz$%9xP`IT9%Q-=L-#oB??r^t%E=VgL@N@(p69QNl@rX+W&)LHKhMi^myA?SFndxDsW{F)ZuO%}hJNU~ zu8J9v)WZo>BKY1xN|5ooin(8DCQyms8y6`-#_KBP)5VnV^Mj{niKsuL$VlZx=^0z` z4xIJM2~?svo6}a2k%}jnDXu@}WU7Qd!O~ONQV%CkiPlw(>qmJel99>@o&uM8_~`n& z!nmab8F@ItHx-%*RHAu$T1wDfsd&nfV)~a7WU2&DooXgf;h}qp{sea!PVn@sW&)Kw zL>EuxD$PVP^h3{zTJ=`(m{C+r=4QOjw?ob$~DD)|wMXbsvv zLy_^iidnmw2~_eR7BMn#(g#m$UzzW)6dA9pm^HYWKqU|2*s7@~JioC0tCuf|e@jBf z>ni42(oCR|2XSoG*lq7UxqZe` zQ^HluJ`t?>DM3amC%AT{1eq$~^Q!lpZK<3sgTZKxk;%b)?%u%WAonCPk zqy%S9mEcaTnLs6)vpFTmNaaNRymA7S=+b&sItR(n58b^eW*(=l;@C=Mcj3j^oDzPX zJHcIlGl5Eeyvs-lGE&()mQ`$(6RMOx6AE@*?@AUe#s{5C|QrUa;SgCj?Tsj`| z;GV$=_T*9zCs4^xXLElK)(ok9EzudAKDk~hGF5_a(59_&0+ndZo?_Raw&$gh?v7#V zVS50jW3y_<1C?4u3sVm=QaPb{+<&Z`K-JuH+jT6yxhg_ySMiLL(pZs^%J$((e^Xt) zMmb@-cnxbJtED`gV8*0l|K(C7L^f)PsyvPUvp1|15C=m1yob zWz?|qo#_KB9TqvIMUrV5p z2eCYc2OkT^V&Y9_M-MVyS21^k%>*iW5Q}IHhS@$DW_$D?<8>8t&)7_$k_WMfI946T zij3D)tZO^RqnmuSc|M2~?^?oO^^7 zuEUy0#_KB9T;Luqu8DmKRPrE}$ME>~!?DnM;u){2SaX{D-FgC*DiP=XsJj}Vl84UC zUOynhZcX8S8KoRV{%^m54?3 zt{xXB&u42t&K8b4;SDY$=O0N^=9$Y^><8>9Y<~I|lREfCg zdAxpj#_KB98k1f>sst*%PMo)j>xXB&u42~wW&)Ke5l2FEH(ozH<8>9Y<~I|lREane zI-}zC!!uqNzx4W1CAenL+JY#q2A=V{idpkxt7-{UszjUIHR!!p!(C@5D&0-;dipzY$}r;;GsBw+wM4b5 zMClwX-aC6O#i)3lwWQn+j;&P8D~SI6@K!nDv%T!$1SX^h@+0W; zs_fydLM0DIM6;w!_*IST>#DcP3BLm{+&I3AIWpRU($h@Ho$P_Keq6%-%^efl8H#bAl&9 zd&cW3W=E%)K&48=1reXD>KU)An4Q9A0+lKe=LAoJ_Keq6%>HFFfl8H#MZ_Z*pX=-y zudDcL_9W*h{A{H@HJPFz}URN=ni!>9cREanzcoMW{yslzCS8XOxsSzv1YjjIzt)8>39mt}VtMs}Pz2`c6rb5Jd zl|Bi&O4zzmtTF0G{pw>xv983P7kB#O`(0S{LosbvELy)IpAuyH5%i;XFY2|3rBckw zmwGU(rDFC$zj~{jD9x)<&%Gb0@GIt3iD31i?fOJ<)mz1i1Cf5BNJc#*mP#=rl8zOl zC>2)#=vN;rCs?&p4<9R3__0#=W+Lu7&U(M>EhLT}#dS~w87CCe!e#;$ttyUSaUJxG z*HuiPau2SYRRWb>CyqpMRr8G3#gDNXsU_48sqpR*T-7||brow2i{Dt+)j;p7FYhStXhYRH{Ur z6I=&9<8>9Yt~3*!4@6u42s+t{?RTDpewuNB!!9N*=5+0(#dd{Z<0MKc<*p15?bnr39HO;XSYS zaGGCHOFhVVOB9!8NpX!*#tBq%}Q3$^5{B&N;JO{nR<|s z$_akGG9}1V3BMYYTjc~Q(fkT$>On>-C-`m9lps?jxF$9es6_j(pO*XK=Qh8{C!+qW zB_ov+{MKIDDko5hW+h4qGEzCgZ|yY`s6^MVaAc%%!heOYJXTJi63x9<+A78!l~x1A z{H|?Ekf{=-`>WDf>jWy%{>#1Peq8y+IoU6=cQ2EQUsaB+vR^DL6W&`V_>JT~{pi+G zT~vze$BImq;P;YK4<}HGW)xC_j8smPeo47Bx=x@HT|c^e&OSJM_GfRKkZQ@p2WNBE z8;-Gd)vn)TYW~-yZU%I zflBn-cKvvE<@7cC5M-os;zygFoUQ)4O;5&ZA|sU(o9{g<+id+`_3>~5mFPpx_(09* zl99@Zsngz@U32mq`;4v=s6;bE(^*1BDkold-~rji)3)v7;RGtt%>2~DkKlgK9-19G z?{%e>C?$NwaYEO@F#ID_pR8IWz>SN=2+)SVn{hBjQ%{KeY-hFybMk*)fOgW+E{BQ!5=zZs( zkxf1BhCUu-q;jJEtaSpF=&dh3J^RBa;`1OY??1>$Xl47oEin$L;2{KiJyPA~nmT;bnu5T3?shnUXN_8*!FRHE5`NC`4hv4gPct#X3hgw(_Pfl40C zv6Nu`NX0vE#mvx@AX6oHPu)zQ63u(+lprG&@1s|}RZeggq#oW6RPx|`LQ0U4%8Ak$ zRos{8Hp-hkw z?Zm%dzFRhT#iuKGeNs7rs<~CPS1KnK-aISYX2F;HcsPMdG$Rs6w=`Ba9KJZ4a{Otr zw|ompgnv7s+;eJ4we?Sr%oc6)_0mYE9=bQw_phqNm47}dTmR%M`t-vIRL!lTy;3=` z!EevWzH-CGeLS2%C7KaQ`{A?1kLJ#sZ;>szbYcEZ0|QyyI>P>JT(T+&vN zk;(~v!6zliR0*|^Z-tdx(a@6+>(4qlX<{?z$1rP4_2Z|xNO_sGf~ zd_PU9wb!~ZJM`Gc?`S5dRV5DjpYyZXJKvr^^Q<)6oj@g;)}~{{Y>;ZZV=l_m|@Z;>n*oTkHo<9GXnau<$`RV*m{~}izt#HhxH_YET+x_Wzu~p2<)Psy@ zCpP%qHrdsSr}vp9PM{K9Kij?SE7mwXJM_AjW2@@>K}L0*SaZex+4OZ*_8BWDQ2B_Y zJ@>J4;(J%^k6ORif|{H~#5eiczMzpt1QjH0U)YaL5}smU`{ zf?w)NJ*XuDm12GkEG3w)Qn3f1m_3J-;5VbB;uohB^V?M^!7h$ejILt#XHtSpmEdSL z6R1RM_7wX*r6Wj2DkqqgsfQD&MAwfM8L6D$yh%NrKqZ>vloIS&O2t{Lm{Cs&GF5_A zqM1M?nxmN#oCi|z3t)P5JZ}Z#|>fiTb&#TKWZ25&SZ#VzoB? z^;6GO2}Y!UKU7NuD#iT1UP_Ru609-J1S-+occlawshr?$FeTXE6~TSGV)m9(f=rd* zokcT&N;G@qDM3amC+hp*1S-*-X{iSpshnWknh8{*IfGMzolU8@zf#O6DJemwN^o!2 zOrVOie^!*NqWYvtD&8R}W-g>2WU2)3+nNbfqM2hU;ce$VjtD-dN(nMjIl+6XW&)LH zT_uXo?rO)%3EoYn9@J7@REintlwglts(IbJV#Um!lps?jxW8^DP>E(%rUX|nskpyZ z%pFHckf{>9dub+6iDpDnf{av7l-?VZj-V5$L^IOz7#@G}f#-*&PhHT~=Mh}b75n`I zaY0OoP%Sc5f_tJe;VQ+bREb!`$k;po^3-Iu^vLKz#tFsT88j29kb`;_ijk@32Ux!N@osN_MM6XBS*Ip$=%u42~8 zW&)Kwh(*M?+h*>P@w$pxW10z6@*s}H_&PU!u>Eh{bC8VJRm|$zOrVknv52^qgg>y# z*Ag;bS1~JJGl5DT#3FjDsAs&cUe|o%-Cb*Z&9lEbwDA@T+uAYbGe{90^QoLX>Iqb; zL@Z!r?DJc!%zpQ+k46tN^6;3?@tO%#@*oz`8h`Ied$#{HcQAU8k%!0rc~m`tN*=^{ ztG@ZfDebKnEXh104^**F{;B?09pRst5l4?{gBvVtZ~y$#i8zYgT3%N%pXoIds8oqq z#PWf!?)K64x%d8Y(lcIHF`qOx6R1>)Sj6z)Zr2R7H<_|m$1`46F`r;I6R1>)I41^g zxjfr$hf|{m8Lz9DZz?nssN_K`qBZ#7Nw-ey_m2h9gN)Zz%x9j>1S)wDix?jK(x;x9 zy!a3E)# z@w$rn{zNl@N*=_qRb!hReNy|YFWs2=Ua?kZe_zYaWUF;cYvXLub7!@eEPH#22!CTx z?1iclpS{Rqcq}~Wt^II#@|S0vQ0zo&K*S^A8CX>U6?Fc4^kzv1 z`(9r?fl8H#<ndi)vzb684`LC+@##r7hGXIxudA57-ev-oDiKE_J_YKga7;Yob@9v3+R&<6 zf}K=a3(*?XSp7O26VG^E#Tvss|Flm0)UuvHrAox=$H>6%L;Y=ok7vBDV)m1p2~?^? z9ErivFiy+E6RkYsbrrLJ-AtfTC1Mf7gWn6sTTjjMjMr7{d*Ss2DpexRJ;JeQ>zH`P z>nhe7!|@m%tRqmV60tm5gFm_Efc6ueH%AXLURN>ed^3T{*Le}WZ+`~&;`d|~AN`lp zviD!MB>uW9Pv%bvGF5`#gN>~ko3_b0oqIRgDEr9^UmKdTe4lK^K~FAI{JvdgXS3$* z7d?2rOsFoIDghmd!LMzy(d1z85wZE1r(`c}yzYbuV!h7qv$k5Vz4J>mei{h1%rj0X z##%Fo1+!IrF3N31fv5Ev4C%lEN*6nll z*=ZmUKkP$z&-pFeyjA}ah!1X>dyw(EY87-O#{W+^dTN<6jJpV8z25sB-Z|eK)#w%k z87CAo3i22pUv1Nkvdy|4PN0$pv54L`QdH~IXAaGdI{(EuuQ(ohUGKJ+exg?ah$VlY` zqn;ApkAW+WDvk{;ObIgbaNsd%`)#7-3aK}!p%kgIn)sNQrOW~OVe+>WPE|n9C8MkHvl`0X7 z7#Vvcv}lXPi{tf!jMr7nxHS`~m)IzD~2SjVIJ60XfcwNPQ z1nUV@szj`QvENfytfl404g~ucwWW26oUrVA#Ujmgph;xrH zR-G`fVn4`uUB#?p%>*iW5JzI*Z(*En3eQgPjMr7n>e@`8QYGR@jCDQY+$H06@zYhJ znP63;wFRMbP-7L(K~!E>vBr>9G@iA62~_eRj;+$lpeM0K4>Dd?vE~9-gSeLTB~ZzO zxbWz^`k<1B<~052U7eNT*wQN94bZCeTI-p91m{QDLoHD)XsHx)rl}ug!pF*w4V6-Y zjOseU>}e)YL9_alTji@LBTAoMeXObk$Gq&}{ZK5GJQ$I*AB>_@tfH&lDkn;7ds|L= zU+A?Iqrxvgqket&4wKS<=$}6ouAsxCAsn5(*6Krw^IuU~edvOfJIvJUuRr$L@Lwm& znKB_dC;tA*E79Zr?;hT9LNThz?XHa;o$RjgUne|MB}C`Mg17G#?*P7k@j%B3#i*Wc zKNLN}?^=fcI^mfrAvz~+zT~9nvG>L|PCB6&)w%1p!q~M&x4Q0@@cmsUJX0k^=Y+pY zbwV*Jdp-ZV)YvM$tME*f=+c3(R%JEB9oD~PWx_M&5sB_71j0tQ?S%DwnH{GJ;h8ES zk8sQbVY8&|gdM?UHs30QXR3re!rTpn&GxnvHWP#D!D-#|CcN`V#rc_WJJXbMI>4nJUqx17ZD`tRZ%{{>>~Co-vO|bVnf&Ho6@rtmiZBI8_MG zR0(#of!t-Ilvwnmk)BRJFMTkvqgGgU$!#TAFyuIoqiP{w9rsO#6Ra1IuPXR1U# IR=V2#KLq2AtpET3 literal 0 HcmV?d00001 diff --git a/src/wroboarm_23/meshes/upperArm_link.STL b/src/wroboarm_23/meshes/upperArm_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..f8a54dcb66fe6f51a512ec4b426e3f5dc8774969 GIT binary patch literal 25984 zcmb`PeXM2GS;n{HFhFczDx`o~bFFg^Uy)wQ#SFRU-ZP+~+N6|JTN8s~3$|b|b*gp1 z@^M-Qu#F08ph-nDe{c_sr7cYXY45rBOo$@2rUh&5432`OV9Q4fr5}zYt?%=$^{n;m zkF}XUoMe(W=Y4#sSy2PO zN{sjX-P)Ib|K*O#m7rC~>W?QcZT@x#QB^?$DWi1Vce#884(pcjwc zwEocEub$J6p(ChcWAv~)1~u@jgvD6yj-dptKyUifj|{(a`%h>cv2xAbtfsK)uY(mv zzlk_-^6Aq%FF39vh7z;_T~*W7yFa$IgLwSZ&rBb@>;5UM=HL9{^t!=$E}wSqFHMj9 z?zg7x?o!hv7`vaKRmf`mvu}FUru8;qy8+k0s!o*ZP=eKhwk{02du5dmS-I6TM76P| zA-d4c%KGCPSSi8S{RFLIO@(=7)w%{&N|ftRf>xkwGjU|T?y&vUVD#|^*SQWt=KcyY z*I=)sNN^2yI#M>T7kC8^B%57sFhXj zyRZT=4&9|MSSi6BV7qc9Xa(BtyLtCo%ZeIUDS>!t&rl?21)6)Uc2?A|4)_i6!d|Qmjo1jMhLawTt@*b{MhZ3}kG4dX+Nw`M+#&~%TS0k)HzAu4Q?OKU@qIMnJ z`!tD;D=N+sC1?d2vAai*8dxd8-B~*;C1?fO#->m?HC{*DO+w}_vmHYTT7jtTscYTk zP6k%Iw?pPS-;Ti*4pzK7L#8JoVt45aR$QqebIlhbu8H&oE2SB`O;FP$I%4Fkd~MfE zAoIS`j=_5^tf0l+GSYt6ZWFwpHwkv3pP*ID%69{8g8KwmDZ#!uF|#|4KhaiHSFD3p(bKRP!!_zR%6Z+bjX5fp7;XiE zeUq$W9lUa2#d!s}c74=hP}3yJGf@dzf#%iR&Wf67wT|Zj$Q;>zf>t27YPSh$)Gy?Y zS(1C@D*&u`Jwmp=b?nCiN#4AL61Qz^$WSGK9u%wWr9|SQB@yK#CF8kuvy|Us8PQ$p6@a-f@Q)o zbgNiLBC3h?YG(6_b+|_TLbgt)J$0F&RqT2qc3{kBHm`ilX{CNcyl^_~GqFf;ryuIb zM1{GF7(RDtrG6QY=Wt~L8N!Nnka%J~_G+dY^&8^lC$BPr@sR60J*zEZWx$ww3|gsQ z$W?ViI-xHUv_iIAW6<65>O&&NORLZJv|fd0^6>ot_CA>TJX@rU7Nmv8t52Cg zr}-@qW%OzxtyiIrV5NQ`^J%i5pcOpv+kr&*dZilm8{?(b$Fu4rEO)nx*(M^dKB`f_ zkgd~c^(hmyf+xzTBd=GgQNJNxUVX|0SE7(@Ci3c|8uiO~Tz$#}a)%YOC6QMj)u`VP zuWP+(5*QD;&eMA3Yl*K{p^jjsej)Q@%4bPh;hF@k@VS0BQC@vW#CU1Fs;cJ?T{rr{ z2^SBsl5zJ6zbf-Nx~l%`z7x&@@xu;+R`A3op3~CUAgx43pyG7;W zZ6KbGF_hp5BnW;EV#n&QJbmTpqU+wXqS4g~vhI+}1g+qSGGbJd+nzpubp2^RGg6KE zg{)63Wr9}lL>VFGCO`J;2Ukuy{@osf8ubf#EZ;$v30ffrWyCmpQjL$g)4J?2s8PRB zUgP(iy@XrE7>PIqb!@N>i{Tpe3)$-P=TBr+CTJCVl?dM?$D*WAy8IHiMNCh)`)@0``2JYSb@eKJWGu zv_cHZAQlF1fB!FUJo$q^@)*>pU&uE9(zA1!pcP`kx1A!`eZ-z|5MzZgs8PQ$o`0Lw zPgsU-73)aE9C|fkuV|%yAzKgq+cU%{6SRusk%%WS<|B?dt<*1M8~^l8T$!L1Vo*j_ zW6a$V=Pots7c%dO{RFKLgR&FpWLq_mXUF{1@UK7r8ozf{)dQ=4e#Y_PJh4XDwKl}x z4uPLFP5z&Wf5QVO^M_ z3;hJGKwmVtX?o4KUfV&iC$Q39=}y012Q^KC_uzI`O3*6Ql+QBiF_7=ucAgo>IXszy zm>qNb^zwU7);jE40M!J)ncyz7ofTJP5ZqHk=Dn*;P}3xIr(dr_30i^XJ-8i%8dxcT zI?~@p)#jBFv;xh&L^}pGp^o4eGEa^A30lP%OWga^E9Y)W{X*vWw_|XQ!iwVznO8xZ zpr%Qb$6N_of#zIj$DjsQN?>gGR1_g)qAD09art*t=nreU$TlZ^i-uz zJh8gt4NH1`>*wfVom88r=FEn>l#=oVey8@u$`3>v;u8iNM|zj7}UT@3G1P+ z;O!Vn&??lCPgv^X!E+c`DFIJBFR5pxnb_D2xe}3}rKb829v1mbnC?Ml!p(BUrHu7i69Sn=KtnfsMCK~0lj?0$k)pkdj4=cEQ!b)vKb zP=fme&^EH^&Y7R+@vKk3@jI6EjWVCS{fQn=6aGXGf*K_tb1wK3J)S1~iM~nD%Fh`( zpXgPie(^bJ)R}i=nhC5}6J(BNKS3*aq6{MM6IG*rA#?Wh6SRUS${_N7S2gMvGUr=A zK`VHo3?lFJRil0(!;&+xOwbCROis@qi|L6)HR?CUOW!D#3CrEBVz!CMPhP4~zmToF z>F*iJ1g+qSGHT0Dkg8F?kZqQv9denV6+BT!jQk|58ubg==COZ2+)vO7o+yJDr&9yf zs9(snQv;mb`KdvZpcOv1YcQT=*r@?d?)=n1HR=~K&jxZ?ddiPn1FA^DEV;U&!2}_7k*%C(0o5Ih<!WE86oodu4>dTWWD2* z30lDuWyDw~IAw70&aba* zIq6a-sKNJ+D&M(r%<|1=|C{ec%LJ_ugEC@NgYVn7)GydyK&S>WXa#xo%3oam;&TT* zMwy@$JW&oYHlK9q=v_O%zM&fR3;Epdziau-OP-1`N(8Ooi85mBn4dpz_2}0Y<~#;9 z>KF2lKla{bzLioYXoVP*J;o|xywOHcHR_k~P8@{yads35WC$zPL1Mgm=)_A$e_`XU z8ubeq-5p*~+1?myVu_#?JW&QwP2!l3RHJ?&WBd>9{ZWrmCTImulo4WX@*%6?WvfLs z>K8KR@k5Uu;W5ett>B3=Vk}PL73DFgQNNI@>Xyk%H*fJ6Wr9|SQB^l5VgWHW?5gz` z)TrMWZ^}B#gk|Vfv5rKXh+b{5SF}>UkgdDx9FHv>K8J4$aS|&(2CXq{gv~trf7wk!L0a~ne7<-yDlAn&Nr!Jyf{%`kZA=O z9Z6@FGaE(!OY%tgSs!GJ;o}UM*|uX)(t=L;FngA+39u+j5F@3u;Sf0 z$oX$M>oNGZoJ|5Tcy}%nv;vK6(>D#Z?otCQB~VlG`fy($XayNvPiL>S7-r=wGOTb7 zVm*&UVeXnQ*E9*xlpDhZLUsBm@89oT1*US`5vER{dGQFUA>G z$PlA;_*p5zIo6*Qtr)K~9^n~)xnun}{H(Zkfj}41%Fx>@Sb<26S~lrpV>AhN0kO9{(EN26 zW(5snkm#tx=5WaOs-;g}@+=7-XMB#oFn;_$p3%x9K~0R22-ML%f(^p0V(c}+(r*E@++hgmJj*m#C*g4Y@{QNp_JI|CtN2dfCnyKv1IuWOkvSpcU&tr$LPI zCer9gdlN}D>Nmub?iLB{E@jUO??)j9uQeYj^~-qdZg?xDi_q>;_861X?Ty1V>lf>Q zFZCPZg_WqE;Ha_dTuT-w_t<-oFIg?BQNNJ65+O#JpcOn(2C*G6HW-5%^&8`*6|PKJ z9c~q~O~h98YQ|pCO8r8%?xyvsOwbB3D5H)s#(c&Rq(=RQc(U#m37bp4I)^$k5#BN3 z+@+QJWjxOIGJy=a`cOt4ehtoe4N{|iL%gu^^%Ll{T<0!>@RebMD+8_6FXXEFKw8_& z1g*ln%6EhE>O&&N^OXo$hJ1r2`t{itKJU7pHwm5j7H^5y zVBRy(FFFcY$L8>|Qi8KbD&My_X=X($#^ZWb&&vGzoh)YP9aT@S6eHXX0+GkO9)lIC zRg9PBRec26MOYz2u8;K8pOq5Ug^qh|$VA6HSTP>2!MM{OFAnh6-296K$Oqo>-1PR> zKJ0IX@vkB3S>fAazI_DwKkxn8@K3(7-+!})e=`N58XUdr!r8UA9Y0gQAWAXn1fwef znV%!X6Z0B_8nr@f{z^%kphgME{2avGt(>8puTFt!~Bd;a!rL#n5zK;3!$@;1h^ z=)a8EPtXc6D1)e0Pk-IDv&{#;x2ziV3z@$z*iX<3o+vvpf6i~bXZDYOcHf3-)GuWI zYGFS?D|n*p#NZtdo;v&8zZv;#r$+rk=C2m^6SP7M${N}`h{Fo z_oQD#EEBXs49bYHfEX)`L5=#2@zU=OmI=$ytzsRC*ot0_*ehD8U&z+O^jniv=n z60rwkKH`|uO8r8%S(1J;vrNzmF({)~Rb_K`#JNk2`i0Ej>+C0Jg&34U?7=lS;x$N( z`h{%QrvH*_KS3+RpbX+DtR*X4OQ=!5kZp}gzxP@uXoVP*5#tS5;g+$&sYd-m=E_%9 z7wx!VsoHbYo$veMbuEHc(No9oy#`+gbrtp8!{-mLrgs6tE_}Q=X%bZxtnfKkSJaVr zmeAOk`|r9!wz2VbFnDUkupP2$nuK+|`75*?1g$`qv(l?pR|(eCu7eu*Rf6l75UE$W zKePhPjKS3*G#g4QI&QVzD%s;%Wl;E}5jzM3DL95uSwEE;< z@d)o=gg1k5j<0XQP)3Yuf)lU*wg2&r3V$0&3CMg4rk|h{JW+O{dd5z0Ua*rK)u`VP zFTY(=6$yP;hB9J|=VOeGP)G2kei<*lT~j3V?HbC6v2}0=r(JeB$U5Ll{f2n?eVj6Z zG2pwelo2EUmPM!|SgBvgn2CH_woK3po~r7uMA$oI@i&B2qkdz&^ma{|u-x4$W}Ao# zy_&ICv{Jv2t-I+>)-pjW#Gs5``7D{)yz()pM*W6(`7P5jVROmfMGbXiV!Uee3Nd`{ z(n|d@9^NZMPGtfa^6fLqAm(rl&Ug({qkcoY@GfCLfll*{L&_j_;P-v}mvlH%uu{K} ztLkg%jl(iQD|q6&gosgIeMrQ3%{LD1`!#5E1a-!6P+sRS7egsF6hzH2N5L4)Xh@7*-oSQs$~wqg}0Y7q<~;v)`XA=+r^ zA8_84zz{5CMBaUKr?9XQ1}hs8Y%<6YB5592#PzMczIDEJ&OSF528LO4*81<^M!p zvu}ps|NGySH+QxlhPPH`9=-A7A6>ropAv`)`eJd+-9rr$ zHnO|^n45YMjA9-AF-KPLAW8`vo896FCc&td;qw=mJ@dZ8NO4{%VKZijId+&}6f}n6 zxudVV)SK<}AWDflzxwXQC*S{SM?(olMIF8hx>@D=P{QnWUqe?Eqas6JU9PdQ{c3C0 z`3IhQ(f6yT-*flVusQSN`3}#!gnQp$hkWq+RlI|n=!tBz~&0>W!2P! z@Ky9~8g1oth;e;PvKk4_e9)Z7^Q`EJOuSv{<@zWZtT3Xoa%*YacMCz!l&}ofxy}~} zMn#6>`=byR<(`Q0cBz;9)gplrL=-g^=hZQ1VkP9wInyA4nUCEW8l1=T@zCDo`=e#m z=G&a$ib9kUTwR9=Mlq}0OG+Kc7al|@VfMI}93ng_>KOOLLSWrtPYjJDxOa8yNPqd;@rfVlQs>!1BFJhOtwW}?6E+RjU9F7zKK{a(WP@1oy7Fh7ybd&0e1q zcrwnu_5}gLDj&ZfCv!Ky2YoKZih`Z1wvIX5YVEct*p{uospnbIGbNzWpY2nE^Vo>a zxg^?k4>d?wUv3EYa~V`)<*ohwa9hvF`1Q1bQ+~vbjIbd)G$Lzr&%Sgk|VE_+f%k zplview+8BoI(U+;dwZ#aZGo_!_B#jIHkzH=5A{q58%=-j&g)=XAQ%<)u0Pu?$~{v8 z8TMz15{#k-Pp`98o9nz1@Qlokb0AOQV8b&k6NJ9Ui6H%ULOb zDAVj{Oxt3VJ@*}Tp4HSt!t^j>`Wo4mMj;yiPK|S0A9fFSwvWm$^}(JpH8tT;pGgnHVkCQq-Kp^sqJF(EQ4M$>zQ#C7j0 z^=ReVhcm+0Hu8-zU{6a;##mNOLvvRGV~@7yl`El9@w|*j(QuCvp|@6zMyQAL3Q_;7 zMw_p#-Lv07Q#IO5tZj`^_8eo=uR}Z|5#!X?NJ68mKI~UXJlgKRc5DCotAC0!PTu?Y zsL8iMzMYo|eecr7Nba_8U4C}|_RpX8cN9J71+{rHI7~1KI|gkKKivNE#{2eP{r3y5 zK@T+4=9%a)!6<0Z261)%m+$=S{@>qu*)`~ahT1&a9VQqB4cZ{aca(ad!Kkp;{B7bO z;Zf0263?xyj#JiQ?Yc+Xjhc@6JI*p;m3vh5RT95m*?4R?9*ojRC_G2Syz8q3 zJxajlbNv1A$TUu=L61g-c76|5!s>935}}vG-IdL&jm<08kpyXISg-q+9&)GzJ=!j8 zJ_m8NvN7Lq%<0jnR>$}~SP2_v|58+<=_!Hr$GNKnZPvl{akWwcS;3?2Qjf#~_LZ+e zC1`Uz_(XP$8{GHp@{F=Atm7qt7meoj9p&wu9*v61 z^UP2Q>l41i3(e=yD5nhcViL4j2Y2d9Am7;A3(e=yD5oXQgao5n9SbKi@7>tj3yogq z+u(0{PAmkYpntKjn>3CG;lMh|{KV19$F8pwCc!)PXzeb*n=OYgasTqGf26Z(3j7 zv+)=S+K96D<)%mp_4J6QVKr<}y`}wOC1|%gaI?+3J|(Qu^vns~g$H5h*x#Ki(d-r# z^hM4qWaWfkyxf6Q7 z+apo~bJqymbZT4UFD6FkEpE}kFhPXANWfE literal 0 HcmV?d00001 diff --git a/src/wroboarm_23/package.xml b/src/wroboarm_23/package.xml new file mode 100644 index 00000000..cb46d45a --- /dev/null +++ b/src/wroboarm_23/package.xml @@ -0,0 +1,41 @@ + + + wroboarm_23 + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the wroboarm_23 with the MoveIt Motion Planning Framework + + Ben Nowotny + Ben Nowotny + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + robot_state_publisher + rviz + tf2_ros + xacro + + + + + + + + + diff --git a/src/wroboarm_23/urdf/ArmAssembly.SLDASM.csv b/src/wroboarm_23/urdf/ArmAssembly.SLDASM.csv new file mode 100644 index 00000000..294889b5 --- /dev/null +++ b/src/wroboarm_23/urdf/ArmAssembly.SLDASM.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,9.1830074983592E-19,-9.80159456515381E-19,0.015606490089144,0,0,0,0.93972387307473,0.00251429022255044,7.37485241366082E-20,8.66637218064247E-21,0.0021336882069818,1.14091331088149E-19,0.0044229329573873,0,0,0,0,0,0,package://wroboarm_23/meshes/base_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/base_link.STL,,base-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +turntable_link,-0.01225868218219,0.128577249577976,-0.00370544350042927,0,0,0,0.996366805002726,0.00652370094208946,0.0010646616036529,0.000283127005277363,0.0050231810993567,6.82113719161566E-05,0.00863345382595838,0,0,0,0,0,0,package://wroboarm_23/meshes/turntable_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/turntable_link.STL,,Shoulder-1,Origin_turntable_joint,Axis1,turntable_joint,continuous,0,0,0.035865,1.5708,0,-0.84509,base_link,0,1,0,,,,,,,,,,,, +upperArm_link,0.0143973999054599,-3.20061625693202E-05,0.279348384794928,0,0,0,0.985210343915811,0.0237982224738338,-8.8797773328906E-07,-0.00388532856230116,0.0293594722597601,-7.129443699684E-06,0.00625034839320102,0,0,0,0,0,0,package://wroboarm_23/meshes/upperArm_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/upperArm_link.STL,,UpperArm-1,Origin_shoulder_joint,Axis2,shoulder_joint,continuous,0,0.18098,0.043071,-1.5572,0,0,turntable_link,-1,0,0,,,,,,,,,,,, +forearm_link,-4.1286418728248E-16,0.0550154986611603,0.120152803034247,0,0,0,0.51779610173045,0.00404850874710764,-4.33680868994202E-19,2.87313575708659E-18,0.00375548329392275,-0.000377385363706531,0.000788327838226511,0,0,0,0,0,0,package://wroboarm_23/meshes/forearm_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/forearm_link.STL,,Forarm-1,Origin_elbowPitch_joint,Axis3,elbowPitch_joint,continuous,0,0,0.46634,2.7009,0,0,upperArm_link,-1,0,0,,,,,,,,,,,, +wrist_link,-2.77555756156289E-17,5.55111512312578E-17,0.096820252622317,0,0,0,0.301763082175336,0.00210344289702837,1.30104260698261E-18,5.14996031930615E-19,0.00305016250706558,-1.15196480826585E-18,0.00107609106501786,0,0,0,0,0,0,package://wroboarm_23/meshes/wrist_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/wrist_link.STL,,WristStructure-1,Origin_elbowRoll_joint,Axis4,elbowRoll_joint,continuous,0,0.04445,0.23038,0,0,0,forearm_link,0,0,1,,,,,,,,,,,, +carpus_link,5.55111512312578E-17,5.55111512312578E-17,0,0,0,0,0.447707117943177,0.000367702266904795,7.04731412115578E-19,1.62630325872826E-19,0.000843427086265753,0,0.000844746123560661,0,0,0,0,0,0,package://wroboarm_23/meshes/carpus_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/carpus_link.STL,,Wrist-1,Origin_wristPitch_joint,Axis5,wristPitch_joint,continuous,0,0,0.23528,0,0,0,wrist_link,-1,0,0,,,,,,,,,,,, +endEffector_link,-0.000725623905114631,-0.000893578002320872,0.0499824104113341,0,0,0,0.399994299548626,0.00169604127916281,-3.07411212276679E-06,2.57918978917245E-05,0.00173351996343527,5.0605971705242E-05,0.000256533582960489,0,0,0,0,0,0,package://wroboarm_23/meshes/endEffector_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_23/meshes/endEffector_link.STL,,Manipulator-1,Origin_wristRoll_link,Axis6,wristRoll_link,continuous,0,0,0,0,0,0,carpus_link,0,0,1,,,,,,,,,,,, diff --git a/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf b/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf new file mode 100644 index 00000000..9f023c40 --- /dev/null +++ b/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf @@ -0,0 +1,365 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file From d4cacd990aaa1991f63cf4a6a863cc3c532eb9be Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Wed, 16 Nov 2022 20:03:25 -0600 Subject: [PATCH 09/33] started fixing the launch files and packages for the new arm --- .../launch/test/mock_arm.launch | 2 +- src/wroboarm_23/.setup_assistant | 2 +- src/wroboarm_23/config/kinematics.yaml | 5 +- src/wroboarm_23/config/wroboarm_23.srdf | 4 +- src/wroboarm_23/launch/demo_test.launch | 69 ++++++++ src/wroboarm_23/launch/moveit.rviz | 167 ++++++++++++++++-- 6 files changed, 227 insertions(+), 22 deletions(-) create mode 100644 src/wroboarm_23/launch/demo_test.launch diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index ca039848..e4278ebd 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -12,7 +12,7 @@ - + diff --git a/src/wroboarm_23/.setup_assistant b/src/wroboarm_23/.setup_assistant index d7285f38..b9e84ea4 100644 --- a/src/wroboarm_23/.setup_assistant +++ b/src/wroboarm_23/.setup_assistant @@ -8,4 +8,4 @@ moveit_setup_assistant_config: CONFIG: author_name: Ben Nowotny author_email: bennowotny65535@gmail.com - generated_timestamp: 1668478000 \ No newline at end of file + generated_timestamp: 1668650009 \ No newline at end of file diff --git a/src/wroboarm_23/config/kinematics.yaml b/src/wroboarm_23/config/kinematics.yaml index 9e26dfee..b003c4be 100644 --- a/src/wroboarm_23/config/kinematics.yaml +++ b/src/wroboarm_23/config/kinematics.yaml @@ -1 +1,4 @@ -{} \ No newline at end of file +arm: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005{} \ No newline at end of file diff --git a/src/wroboarm_23/config/wroboarm_23.srdf b/src/wroboarm_23/config/wroboarm_23.srdf index c1a526cc..f3d67e92 100644 --- a/src/wroboarm_23/config/wroboarm_23.srdf +++ b/src/wroboarm_23/config/wroboarm_23.srdf @@ -13,9 +13,9 @@ - + - + diff --git a/src/wroboarm_23/launch/demo_test.launch b/src/wroboarm_23/launch/demo_test.launch new file mode 100644 index 00000000..bfafe199 --- /dev/null +++ b/src/wroboarm_23/launch/demo_test.launch @@ -0,0 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [control/arm_joint_states] + + + + [control/arm_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/wroboarm_23/launch/moveit.rviz b/src/wroboarm_23/launch/moveit.rviz index 6a876dde..627612c8 100644 --- a/src/wroboarm_23/launch/moveit.rviz +++ b/src/wroboarm_23/launch/moveit.rviz @@ -5,8 +5,9 @@ Panels: Property Tree Widget: Expanded: - /MotionPlanning1 + - /Pose1 Splitter Ratio: 0.5 - Tree Height: 226 + Tree Height: 295 - Class: rviz/Help Name: Help - Class: rviz/Views @@ -14,6 +15,10 @@ Panels: - /Current View1 Name: Views Splitter Ratio: 0.5 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -23,7 +28,7 @@ Visualization Manager: Color: 160; 160; 164 Enabled: true Line Style: - Line Width: 0.03 + Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 @@ -35,30 +40,96 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: true - - Class: moveit_rviz_plugin/MotionPlanning + - Acceleration_Scaling_Factor: 0.1 + Class: moveit_rviz_plugin/MotionPlanning Enabled: true + Move Group Namespace: "" + MoveIt_Allow_Approximate_IK: false + MoveIt_Allow_External_Program: false + MoveIt_Allow_Replanning: false + MoveIt_Allow_Sensor_Positioning: false + MoveIt_Planning_Attempts: 10 + MoveIt_Planning_Time: 5 + MoveIt_Use_Cartesian_Path: false + MoveIt_Use_Constraint_Aware_IK: false + MoveIt_Workspace: + Center: + X: 0 + Y: 0 + Z: 0 + Size: + X: 2 + Y: 2 + Z: 2 Name: MotionPlanning Planned Path: - Links: ~ + Color Enabled: false + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + carpus_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + endEffector_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + turntable_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperArm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true Loop Animation: true Robot Alpha: 0.5 + Robot Color: 150; 50; 150 Show Robot Collision: false Show Robot Visual: true Show Trail: false State Display Time: 0.05 s + Trail Step Size: 1 Trajectory Topic: move_group/display_planned_path + Use Sim Time: false Planning Metrics: Payload: 1 Show Joint Torques: false Show Manipulability: false Show Manipulability Index: false Show Weight Limit: false + TextHeight: 0.07999999821186066 Planning Request: Colliding Link Color: 255; 0; 0 Goal State Alpha: 1 Goal State Color: 250; 128; 0 Interactive Marker Size: 0 Joint Violation Color: 255; 0; 255 + Planning Group: arm Query Goal State: true Query Start State: false Show Workspace: false @@ -68,19 +139,81 @@ Visualization Manager: Robot Description: robot_description Scene Geometry: Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.009999999776482582 Show Scene Geometry: true Voxel Coloring: Z-Axis Voxel Rendering: Occupied Voxels Scene Robot: Attached Body Color: 150; 50; 150 - Links: ~ + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + carpus_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + endEffector_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + turntable_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperArm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true Robot Alpha: 0.5 - Show Scene Robot: true + Show Robot Collision: false + Show Robot Visual: true + Value: true + Velocity_Scaling_Factor: 0.1 + - Alpha: 1 + Axes Length: 0.10000000149011612 + Axes Radius: 0.02500000037252903 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Axes + Topic: /logic/arm_teleop/next_target + Unreliable: false Value: true Enabled: true Global Options: Background Color: 48; 48; 48 + Default Light: true Fixed Frame: base_link + Frame Rate: 30 Name: root Tools: - Class: rviz/Interact @@ -91,22 +224,22 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 2.0 + Distance: 2 Enable Stereo Rendering: - Stereo Eye Separation: 0.06 + Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Field of View: 0.75 Focal Point: - X: -0.1 + X: -0.10000000149011612 Y: 0.25 - Z: 0.30 + Z: 0.30000001192092896 Focal Shape Fixed Size: true - Focal Shape Size: 0.05 + Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View - Near Clip Distance: 0.01 + Near Clip Distance: 0.009999999776482582 Pitch: 0.5 Target Frame: base_link Yaw: -0.6232355833053589 @@ -114,7 +247,7 @@ Visualization Manager: Window Geometry: Displays: collapsed: false - Height: 848 + Height: 1016 Help: collapsed: false Hide Left Dock: false @@ -123,9 +256,9 @@ Window Geometry: collapsed: false MotionPlanning - Trajectory Slider: collapsed: false - QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000100000000000001f30000039efc0200000007fb000000100044006900730070006c006100790073010000003d000001b8000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001fb000001e00000017d00ffffff0000053f0000039e00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Views: collapsed: false - Width: 1291 - X: 454 - Y: 25 + Width: 1848 + X: 72 + Y: 27 From 1d61fbe9fb47b2c463f5b82f573ca4180ad1e99d Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 21 Nov 2022 19:54:44 -0600 Subject: [PATCH 10/33] Changed the names of the joints in the control layer --- .../src/ArmControlSystem.cpp | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/src/wr_control_drive_arm/src/ArmControlSystem.cpp b/src/wr_control_drive_arm/src/ArmControlSystem.cpp index 8da28047..b70b54ec 100644 --- a/src/wr_control_drive_arm/src/ArmControlSystem.cpp +++ b/src/wr_control_drive_arm/src/ArmControlSystem.cpp @@ -222,20 +222,20 @@ auto main(int argc, char** argv) ->int pn.getParam("encoder_parameters", encParams); // Initialize all motors with their MoveIt name, WRoboclaw initialization, and reference to the current node - auto elbow = std::make_unique("elbow", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n); - auto forearmRoll = std::make_unique("forearm_roll", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n); - auto shoulder = std::make_unique("shoulder", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n); - auto turntable = std::make_unique("turntable", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n); - auto wristLeft = std::make_unique("wrist_pitch", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n); - auto wristRight = std::make_unique("wrist_roll", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n); + auto elbowPitch_joint = std::make_unique("elbowPitch_joint", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n); + auto elbowRoll_joint = std::make_unique("elbowRoll_joint", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n); + auto shoulder_joint = std::make_unique("shoulder_joint", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n); + auto turntable_joint = std::make_unique("turntable_joint", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n); + auto wristPitch_joint = std::make_unique("wristPitch_joint", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n); + auto wristRoll_link = std::make_unique("wristRoll_link", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n); std::cout << "init motors" << std::endl; // Initialize all Joints - joints.at(0) = std::make_unique(std::move(elbow), n); - joints.at(1) = std::make_unique(std::move(forearmRoll), n); - joints.at(2) = std::make_unique(std::move(shoulder), n); - joints.at(3) = std::make_unique(std::move(turntable), n); - joints.at(4) = std::make_unique(std::move(wristLeft), std::move(wristRight), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); + joints.at(0) = std::make_unique(std::move(turntable_joint), n); + joints.at(1) = std::make_unique(std::move(shoulder_joint), n); + joints.at(2) = std::make_unique(std::move(elbowPitch_joint), n); + joints.at(3) = std::make_unique(std::move(elbowRoll_joint), n); + joints.at(4) = std::make_unique(std::move(wristPitch_joint), std::move(wristRoll_link), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); std::cout << "init joints" << std::endl; // Initialize the Joint State Data Publisher From 8b48efa39432b6d29dfe20f746b039c19810c422 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 21 Nov 2022 20:00:45 -0600 Subject: [PATCH 11/33] Generated new moveit package --- src/wroboarm_23/.setup_assistant | 2 +- src/wroboarm_23/config/kinematics.yaml | 2 +- src/wroboarm_23/config/ros_controllers.yaml | 40 --------------------- src/wroboarm_23/package.xml | 2 +- 4 files changed, 3 insertions(+), 43 deletions(-) diff --git a/src/wroboarm_23/.setup_assistant b/src/wroboarm_23/.setup_assistant index b9e84ea4..ccd64ddc 100644 --- a/src/wroboarm_23/.setup_assistant +++ b/src/wroboarm_23/.setup_assistant @@ -8,4 +8,4 @@ moveit_setup_assistant_config: CONFIG: author_name: Ben Nowotny author_email: bennowotny65535@gmail.com - generated_timestamp: 1668650009 \ No newline at end of file + generated_timestamp: 1669082391 \ No newline at end of file diff --git a/src/wroboarm_23/config/kinematics.yaml b/src/wroboarm_23/config/kinematics.yaml index b003c4be..05573e5c 100644 --- a/src/wroboarm_23/config/kinematics.yaml +++ b/src/wroboarm_23/config/kinematics.yaml @@ -1,4 +1,4 @@ arm: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005{} \ No newline at end of file + kinematics_solver_timeout: 0.005 \ No newline at end of file diff --git a/src/wroboarm_23/config/ros_controllers.yaml b/src/wroboarm_23/config/ros_controllers.yaml index 537c68ae..e69de29b 100644 --- a/src/wroboarm_23/config/ros_controllers.yaml +++ b/src/wroboarm_23/config/ros_controllers.yaml @@ -1,40 +0,0 @@ -arm_controller: - type: effort_controllers/JointTrajectoryController - joints: - - turntable_joint - - shoulder_joint - - elbowPitch_joint - - elbowRoll_joint - - wristPitch_joint - - wristRoll_link - gains: - turntable_joint: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - shoulder_joint: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - elbowPitch_joint: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - elbowRoll_joint: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - wristPitch_joint: - p: 100 - d: 1 - i: 1 - i_clamp: 1 - wristRoll_link: - p: 100 - d: 1 - i: 1 - i_clamp: 1 \ No newline at end of file diff --git a/src/wroboarm_23/package.xml b/src/wroboarm_23/package.xml index cb46d45a..504f2798 100644 --- a/src/wroboarm_23/package.xml +++ b/src/wroboarm_23/package.xml @@ -35,7 +35,7 @@ - + wroboarm_23 From 929eddc603350dd5ba98076479ef7c62e5881b15 Mon Sep 17 00:00:00 2001 From: Ben Nowotny Date: Tue, 22 Nov 2022 19:57:10 -0600 Subject: [PATCH 12/33] Removing self-dependency --- src/wroboarm_23/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/src/wroboarm_23/package.xml b/src/wroboarm_23/package.xml index 504f2798..ee8c34af 100644 --- a/src/wroboarm_23/package.xml +++ b/src/wroboarm_23/package.xml @@ -35,7 +35,6 @@ - wroboarm_23 From 853dd98d1cc56fcf838e77880c8368dd6dc24940 Mon Sep 17 00:00:00 2001 From: Ben Nowotny Date: Wed, 23 Nov 2022 01:31:47 -0600 Subject: [PATCH 13/33] cleanup and fixes, works again --- src/arm_assembly/CMakeLists.txt | 14 - .../config/joint_names_arm_assembly.yaml | 1 - src/arm_assembly/export.log | 566 ------------------ src/arm_assembly/launch/display.launch | 20 - src/arm_assembly/launch/gazebo.launch | 20 - src/arm_assembly/meshes/base_link.STL | Bin 11984 -> 0 bytes src/arm_assembly/meshes/forarm_link.STL | Bin 19984 -> 0 bytes src/arm_assembly/meshes/manipulator_link.STL | Bin 54284 -> 0 bytes src/arm_assembly/meshes/shoulderBase_link.STL | Bin 53584 -> 0 bytes src/arm_assembly/meshes/upperArm_link.STL | Bin 25984 -> 0 bytes src/arm_assembly/meshes/wirstBase_link.STL | Bin 12484 -> 0 bytes src/arm_assembly/meshes/wrist_link.STL | Bin 50884 -> 0 bytes src/arm_assembly/package.xml | 21 - src/arm_assembly/urdf/arm_assembly.csv | 8 - src/arm_assembly/urdf/arm_assembly.urdf | 282 --------- .../src/ArmControlSystem.cpp | 43 +- src/wr_control_drive_arm/src/ArmMotor.cpp | 14 +- .../launch/test/mock_arm.launch | 2 +- src/wr_logic_teleop_arm/launch/std.launch | 3 +- .../src/ArmTeleopLogic.cpp | 4 +- src/wroboarm_21/.setup_assistant | 11 - src/wroboarm_21/CMakeLists.txt | 10 - src/wroboarm_21/config/cartesian_limits.yaml | 5 - src/wroboarm_21/config/chomp_planning.yaml | 18 - src/wroboarm_21/config/fake_controllers.yaml | 13 - src/wroboarm_21/config/joint_limits.yaml | 45 -- .../config/joint_names_wroboarm_21.yaml | 1 - src/wroboarm_21/config/kinematics.yaml | 4 - src/wroboarm_21/config/ompl_planning.yaml | 156 ----- src/wroboarm_21/config/ros_controllers.yaml | 37 -- src/wroboarm_21/config/sensors_3d.yaml | 10 - src/wroboarm_21/config/wroboarm_21.srdf | 38 -- src/wroboarm_21/export.log | 365 ----------- .../launch/chomp_planning_pipeline.launch.xml | 21 - .../launch/default_warehouse_db.launch | 15 - src/wroboarm_21/launch/demo.launch | 64 -- src/wroboarm_21/launch/demo_gazebo.launch | 74 --- src/wroboarm_21/launch/demo_test.launch | 66 -- src/wroboarm_21/launch/display.launch | 20 - .../fake_moveit_controller_manager.launch.xml | 9 - src/wroboarm_21/launch/gazebo.launch | 23 - .../launch/joystick_control.launch | 17 - src/wroboarm_21/launch/move_group.launch | 82 --- src/wroboarm_21/launch/moveit.rviz | 276 --------- src/wroboarm_21/launch/moveit_rviz.launch | 15 - .../launch/ompl_planning_pipeline.launch.xml | 25 - ...otion_planner_planning_pipeline.launch.xml | 19 - .../launch/planning_context.launch | 25 - .../launch/planning_pipeline.launch.xml | 10 - src/wroboarm_21/launch/ros_controllers.launch | 11 - .../launch/run_benchmark_ompl.launch | 21 - .../launch/sensor_manager.launch.xml | 17 - src/wroboarm_21/launch/setup_assistant.launch | 15 - .../launch/trajectory_execution.launch.xml | 20 - src/wroboarm_21/launch/warehouse.launch | 15 - .../launch/warehouse_settings.launch.xml | 16 - ...rm_21_moveit_controller_manager.launch.xml | 10 - ...oboarm_21_moveit_sensor_manager.launch.xml | 3 - src/wroboarm_21/meshes/elbow.STL | Bin 8084 -> 0 bytes src/wroboarm_21/meshes/forearm.STL | Bin 14084 -> 0 bytes src/wroboarm_21/meshes/gearbox.STL | Bin 12884 -> 0 bytes src/wroboarm_21/meshes/manipulator.STL | Bin 4884 -> 0 bytes src/wroboarm_21/meshes/turntable.STL | Bin 4484 -> 0 bytes src/wroboarm_21/meshes/upperarm.STL | Bin 13484 -> 0 bytes src/wroboarm_21/meshes/wrist.STL | Bin 21884 -> 0 bytes src/wroboarm_21/package.xml | 35 -- src/wroboarm_21/urdf/wroboarm_21.csv | 8 - src/wroboarm_21/urdf/wroboarm_21.urdf | 306 ---------- src/wroboarm_22/.setup_assistant | 11 - src/wroboarm_22/CMakeLists.txt | 14 - src/wroboarm_22/config/arm_assembly.srdf | 43 -- src/wroboarm_22/config/cartesian_limits.yaml | 5 - src/wroboarm_22/config/chomp_planning.yaml | 18 - src/wroboarm_22/config/fake_controllers.yaml | 15 - .../config/gazebo_controllers.yaml | 4 - src/wroboarm_22/config/joint_limits.yaml | 52 -- .../config/joint_names_wroboarm_22.yaml | 1 - src/wroboarm_22/config/kinematics.yaml | 4 - src/wroboarm_22/config/ompl_planning.yaml | 155 ----- src/wroboarm_22/config/ros_controllers.yaml | 35 -- src/wroboarm_22/config/sensors_3d.yaml | 10 - .../config/simple_moveit_controllers.yaml | 23 - src/wroboarm_22/config/wroboarm_22.srdf | 34 -- src/wroboarm_22/export.log | 566 ------------------ ..._assembly_moveit_sensor_manager.launch.xml | 3 - .../launch/chomp_planning_pipeline.launch.xml | 25 - .../launch/default_warehouse_db.launch | 15 - src/wroboarm_22/launch/demo.launch | 67 --- src/wroboarm_22/launch/demo_gazebo.launch | 73 --- src/wroboarm_22/launch/demo_test.launch | 67 --- src/wroboarm_22/launch/display.launch | 20 - .../fake_moveit_controller_manager.launch.xml | 12 - src/wroboarm_22/launch/gazebo copy.launch | 23 - src/wroboarm_22/launch/gazebo.launch | 20 - .../launch/joystick_control.launch | 17 - src/wroboarm_22/launch/move_group.launch | 104 ---- src/wroboarm_22/launch/moveit.rviz | 339 ----------- src/wroboarm_22/launch/moveit_rviz.launch | 15 - .../launch/ompl_planning_pipeline.launch.xml | 28 - ...otion_planner_planning_pipeline.launch.xml | 19 - .../launch/planning_context.launch | 26 - .../launch/planning_pipeline.launch.xml | 10 - ...ntrol_moveit_controller_manager.launch.xml | 4 - src/wroboarm_22/launch/ros_controllers.launch | 11 - .../launch/run_benchmark_ompl.launch | 21 - .../launch/sensor_manager.launch.xml | 17 - src/wroboarm_22/launch/setup_assistant.launch | 15 - ...imple_moveit_controller_manager.launch.xml | 8 - .../launch/trajectory_execution.launch.xml | 24 - src/wroboarm_22/launch/warehouse.launch | 15 - .../launch/warehouse_settings.launch.xml | 16 - ...rm_22_moveit_controller_manager.launch.xml | 10 - ...oboarm_22_moveit_sensor_manager.launch.xml | 3 - src/wroboarm_22/meshes/base_link.stl | Bin 11984 -> 0 bytes src/wroboarm_22/meshes/forarm_link.stl | Bin 19984 -> 0 bytes src/wroboarm_22/meshes/manipulator_link.stl | Bin 54284 -> 0 bytes src/wroboarm_22/meshes/shoulderBase_link.stl | Bin 53584 -> 0 bytes src/wroboarm_22/meshes/upperArm_link.stl | Bin 25984 -> 0 bytes src/wroboarm_22/meshes/wirstBase_link.stl | Bin 12484 -> 0 bytes src/wroboarm_22/meshes/wrist_link.stl | Bin 50884 -> 0 bytes src/wroboarm_22/package.xml | 36 -- src/wroboarm_22/urdf/wroboarm_22.csv | 8 - src/wroboarm_22/urdf/wroboarm_22.urdf | 281 --------- src/wroboarm_23/config/ros_controllers.yaml | 12 + src/wroboarm_23/launch/demo_test.launch | 2 +- src/wroboarm_23/launch/moveit.rviz | 3 +- test_arm_control_stack.sh | 4 +- 127 files changed, 53 insertions(+), 5259 deletions(-) delete mode 100644 src/arm_assembly/CMakeLists.txt delete mode 100644 src/arm_assembly/config/joint_names_arm_assembly.yaml delete mode 100644 src/arm_assembly/export.log delete mode 100644 src/arm_assembly/launch/display.launch delete mode 100644 src/arm_assembly/launch/gazebo.launch delete mode 100644 src/arm_assembly/meshes/base_link.STL delete mode 100644 src/arm_assembly/meshes/forarm_link.STL delete mode 100644 src/arm_assembly/meshes/manipulator_link.STL delete mode 100644 src/arm_assembly/meshes/shoulderBase_link.STL delete mode 100644 src/arm_assembly/meshes/upperArm_link.STL delete mode 100644 src/arm_assembly/meshes/wirstBase_link.STL delete mode 100644 src/arm_assembly/meshes/wrist_link.STL delete mode 100644 src/arm_assembly/package.xml delete mode 100644 src/arm_assembly/urdf/arm_assembly.csv delete mode 100644 src/arm_assembly/urdf/arm_assembly.urdf delete mode 100644 src/wroboarm_21/.setup_assistant delete mode 100644 src/wroboarm_21/CMakeLists.txt delete mode 100644 src/wroboarm_21/config/cartesian_limits.yaml delete mode 100644 src/wroboarm_21/config/chomp_planning.yaml delete mode 100644 src/wroboarm_21/config/fake_controllers.yaml delete mode 100644 src/wroboarm_21/config/joint_limits.yaml delete mode 100644 src/wroboarm_21/config/joint_names_wroboarm_21.yaml delete mode 100644 src/wroboarm_21/config/kinematics.yaml delete mode 100644 src/wroboarm_21/config/ompl_planning.yaml delete mode 100644 src/wroboarm_21/config/ros_controllers.yaml delete mode 100644 src/wroboarm_21/config/sensors_3d.yaml delete mode 100644 src/wroboarm_21/config/wroboarm_21.srdf delete mode 100644 src/wroboarm_21/export.log delete mode 100644 src/wroboarm_21/launch/chomp_planning_pipeline.launch.xml delete mode 100644 src/wroboarm_21/launch/default_warehouse_db.launch delete mode 100644 src/wroboarm_21/launch/demo.launch delete mode 100644 src/wroboarm_21/launch/demo_gazebo.launch delete mode 100644 src/wroboarm_21/launch/demo_test.launch delete mode 100644 src/wroboarm_21/launch/display.launch delete mode 100644 src/wroboarm_21/launch/fake_moveit_controller_manager.launch.xml delete mode 100644 src/wroboarm_21/launch/gazebo.launch delete mode 100644 src/wroboarm_21/launch/joystick_control.launch delete mode 100644 src/wroboarm_21/launch/move_group.launch delete mode 100644 src/wroboarm_21/launch/moveit.rviz delete mode 100644 src/wroboarm_21/launch/moveit_rviz.launch delete mode 100644 src/wroboarm_21/launch/ompl_planning_pipeline.launch.xml delete mode 100644 src/wroboarm_21/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml delete mode 100644 src/wroboarm_21/launch/planning_context.launch delete mode 100644 src/wroboarm_21/launch/planning_pipeline.launch.xml delete mode 100644 src/wroboarm_21/launch/ros_controllers.launch delete mode 100644 src/wroboarm_21/launch/run_benchmark_ompl.launch delete mode 100644 src/wroboarm_21/launch/sensor_manager.launch.xml delete mode 100644 src/wroboarm_21/launch/setup_assistant.launch delete mode 100644 src/wroboarm_21/launch/trajectory_execution.launch.xml delete mode 100644 src/wroboarm_21/launch/warehouse.launch delete mode 100644 src/wroboarm_21/launch/warehouse_settings.launch.xml delete mode 100644 src/wroboarm_21/launch/wroboarm_21_moveit_controller_manager.launch.xml delete mode 100644 src/wroboarm_21/launch/wroboarm_21_moveit_sensor_manager.launch.xml delete mode 100644 src/wroboarm_21/meshes/elbow.STL delete mode 100644 src/wroboarm_21/meshes/forearm.STL delete mode 100644 src/wroboarm_21/meshes/gearbox.STL delete mode 100644 src/wroboarm_21/meshes/manipulator.STL delete mode 100644 src/wroboarm_21/meshes/turntable.STL delete mode 100644 src/wroboarm_21/meshes/upperarm.STL delete mode 100644 src/wroboarm_21/meshes/wrist.STL delete mode 100644 src/wroboarm_21/package.xml delete mode 100644 src/wroboarm_21/urdf/wroboarm_21.csv delete mode 100644 src/wroboarm_21/urdf/wroboarm_21.urdf delete mode 100644 src/wroboarm_22/.setup_assistant delete mode 100644 src/wroboarm_22/CMakeLists.txt delete mode 100644 src/wroboarm_22/config/arm_assembly.srdf delete mode 100644 src/wroboarm_22/config/cartesian_limits.yaml delete mode 100644 src/wroboarm_22/config/chomp_planning.yaml delete mode 100644 src/wroboarm_22/config/fake_controllers.yaml delete mode 100644 src/wroboarm_22/config/gazebo_controllers.yaml delete mode 100644 src/wroboarm_22/config/joint_limits.yaml delete mode 100644 src/wroboarm_22/config/joint_names_wroboarm_22.yaml delete mode 100644 src/wroboarm_22/config/kinematics.yaml delete mode 100644 src/wroboarm_22/config/ompl_planning.yaml delete mode 100644 src/wroboarm_22/config/ros_controllers.yaml delete mode 100644 src/wroboarm_22/config/sensors_3d.yaml delete mode 100644 src/wroboarm_22/config/simple_moveit_controllers.yaml delete mode 100644 src/wroboarm_22/config/wroboarm_22.srdf delete mode 100644 src/wroboarm_22/export.log delete mode 100644 src/wroboarm_22/launch/arm_assembly_moveit_sensor_manager.launch.xml delete mode 100644 src/wroboarm_22/launch/chomp_planning_pipeline.launch.xml delete mode 100644 src/wroboarm_22/launch/default_warehouse_db.launch delete mode 100644 src/wroboarm_22/launch/demo.launch delete mode 100644 src/wroboarm_22/launch/demo_gazebo.launch delete mode 100644 src/wroboarm_22/launch/demo_test.launch delete mode 100644 src/wroboarm_22/launch/display.launch delete mode 100644 src/wroboarm_22/launch/fake_moveit_controller_manager.launch.xml delete mode 100644 src/wroboarm_22/launch/gazebo copy.launch delete mode 100644 src/wroboarm_22/launch/gazebo.launch delete mode 100644 src/wroboarm_22/launch/joystick_control.launch delete mode 100644 src/wroboarm_22/launch/move_group.launch delete mode 100644 src/wroboarm_22/launch/moveit.rviz delete mode 100644 src/wroboarm_22/launch/moveit_rviz.launch delete mode 100644 src/wroboarm_22/launch/ompl_planning_pipeline.launch.xml delete mode 100644 src/wroboarm_22/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml delete mode 100644 src/wroboarm_22/launch/planning_context.launch delete mode 100644 src/wroboarm_22/launch/planning_pipeline.launch.xml delete mode 100644 src/wroboarm_22/launch/ros_control_moveit_controller_manager.launch.xml delete mode 100644 src/wroboarm_22/launch/ros_controllers.launch delete mode 100644 src/wroboarm_22/launch/run_benchmark_ompl.launch delete mode 100644 src/wroboarm_22/launch/sensor_manager.launch.xml delete mode 100644 src/wroboarm_22/launch/setup_assistant.launch delete mode 100644 src/wroboarm_22/launch/simple_moveit_controller_manager.launch.xml delete mode 100644 src/wroboarm_22/launch/trajectory_execution.launch.xml delete mode 100644 src/wroboarm_22/launch/warehouse.launch delete mode 100644 src/wroboarm_22/launch/warehouse_settings.launch.xml delete mode 100644 src/wroboarm_22/launch/wroboarm_22_moveit_controller_manager.launch.xml delete mode 100644 src/wroboarm_22/launch/wroboarm_22_moveit_sensor_manager.launch.xml delete mode 100644 src/wroboarm_22/meshes/base_link.stl delete mode 100644 src/wroboarm_22/meshes/forarm_link.stl delete mode 100644 src/wroboarm_22/meshes/manipulator_link.stl delete mode 100644 src/wroboarm_22/meshes/shoulderBase_link.stl delete mode 100644 src/wroboarm_22/meshes/upperArm_link.stl delete mode 100644 src/wroboarm_22/meshes/wirstBase_link.stl delete mode 100644 src/wroboarm_22/meshes/wrist_link.stl delete mode 100644 src/wroboarm_22/package.xml delete mode 100644 src/wroboarm_22/urdf/wroboarm_22.csv delete mode 100644 src/wroboarm_22/urdf/wroboarm_22.urdf diff --git a/src/arm_assembly/CMakeLists.txt b/src/arm_assembly/CMakeLists.txt deleted file mode 100644 index 22bc5ed7..00000000 --- a/src/arm_assembly/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) - -project(arm_assembly) - -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/src/arm_assembly/config/joint_names_arm_assembly.yaml b/src/arm_assembly/config/joint_names_arm_assembly.yaml deleted file mode 100644 index 159fc6fe..00000000 --- a/src/arm_assembly/config/joint_names_arm_assembly.yaml +++ /dev/null @@ -1 +0,0 @@ -controller_joint_names: ['', 'turntable', 'shoulder', 'elbow', 'forearm_roll', 'wrist_pitch', 'wrist_roll', ] diff --git a/src/arm_assembly/export.log b/src/arm_assembly/export.log deleted file mode 100644 index 0f28f844..00000000 --- a/src/arm_assembly/export.log +++ /dev/null @@ -1,566 +0,0 @@ -2022-01-28 23:47:18,488 INFO Logger.cs: 70 - --------------------------------------------------------------------------------- -2022-01-28 23:47:18,508 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter -2022-01-28 23:47:18,508 INFO Logger.cs: 73 - Commit version 1.6.0-4-g7f85cfe -2022-01-28 23:47:18,509 INFO Logger.cs: 74 - Build version 1.6.7995.38578 -2022-01-28 23:47:18,510 INFO SwAddin.cs: 192 - Attempting to connect to SW -2022-01-28 23:47:18,511 INFO SwAddin.cs: 197 - Setting up callbacks -2022-01-28 23:47:18,511 INFO SwAddin.cs: 201 - Setting up command manager -2022-01-28 23:47:18,512 INFO SwAddin.cs: 204 - Adding command manager -2022-01-28 23:47:18,517 INFO SwAddin.cs: 263 - Adding Assembly export to file menu -2022-01-28 23:47:18,517 INFO SwAddin.cs: 272 - Adding Part export to file menu -2022-01-28 23:47:18,518 INFO SwAddin.cs: 210 - Adding event handlers -2022-01-28 23:47:18,520 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks -2022-01-29 04:01:04,989 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM -2022-01-29 04:01:07,687 INFO SwAddin.cs: 313 - Saving assembly -2022-01-29 04:01:07,864 INFO SwAddin.cs: 316 - Opening property manager -2022-01-29 04:01:07,891 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:01:07,894 INFO ExportHelperExtension.cs: 1136 - Found 44 in ArmAssembly.SLDASM -2022-01-29 04:01:07,894 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:01:07,895 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:07,895 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:07,930 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:01:07,930 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:07,931 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:01:07,931 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:01:07,931 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:07,932 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:01:07,932 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:01:07,932 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:07,933 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:01:07,933 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:01:07,934 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:07,934 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:01:07,934 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:07,936 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:01:07,936 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:01:07,936 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:07,937 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:01:07,937 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1136 - Found 44 in ArmAssembly.SLDASM -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:07,939 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:01:07,939 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:07,939 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:01:07,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:01:07,940 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:07,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:01:07,942 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:07,942 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:01:07,942 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:01:07,943 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:07,943 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:01:07,943 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:01:07,944 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:07,944 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:01:07,944 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:01:07,945 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:07,945 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:01:08,306 INFO SwAddin.cs: 339 - Loading config tree -2022-01-29 04:01:08,309 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration -2022-01-29 04:01:08,315 INFO SwAddin.cs: 344 - Showing property manager -2022-01-29 04:01:36,796 INFO ExportPropertyManager.cs: 422 - Configuration saved -2022-01-29 04:01:38,889 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:01:38,895 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:38,895 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:01:38,895 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:38,896 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:38,896 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:01:38,896 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:38,897 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:01:38,897 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:01:38,897 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:38,898 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:01:38,898 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:01:38,899 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:38,899 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:01:38,899 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:01:38,900 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:38,900 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:01:38,900 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:01:38,901 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:38,901 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:01:38,902 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:01:38,902 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:38,902 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:01:38,903 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:01:38,903 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:38,903 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:01:38,904 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:01:38,904 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:38,904 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:01:38,905 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:38,905 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:38,905 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:01:38,906 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:38,906 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:01:38,906 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:38,908 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:01:38,908 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:01:38,908 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:38,909 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:01:38,909 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:01:38,909 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:38,910 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:01:38,910 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:01:38,910 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:38,911 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:01:38,911 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:01:38,911 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:38,912 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:01:38,958 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:01:48,808 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM -2022-01-29 04:01:48,808 INFO SwAddin.cs: 299 - Save is required -2022-01-29 04:01:48,809 INFO SwAddin.cs: 313 - Saving assembly -2022-01-29 04:01:49,233 INFO SwAddin.cs: 316 - Opening property manager -2022-01-29 04:01:49,234 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:01:49,235 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:49,235 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:01:49,235 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:49,236 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:49,236 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:01:49,236 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:49,237 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:01:49,237 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:01:49,237 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:49,238 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:01:49,238 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:01:49,238 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:49,239 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:01:49,239 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:01:49,240 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:49,240 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:01:49,240 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:01:49,241 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:49,241 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:01:49,241 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:01:49,242 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:49,248 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:01:49,248 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:01:49,279 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:49,279 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:49,281 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:49,281 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:01:49,282 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:49,282 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:01:49,282 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:01:49,283 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:49,283 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:01:49,283 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:01:49,284 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:49,284 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:01:49,285 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:01:49,285 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:49,285 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:01:49,286 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:01:49,286 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:01:49,288 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:01:49,288 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:49,288 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:01:49,398 INFO SwAddin.cs: 339 - Loading config tree -2022-01-29 04:01:49,400 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:01:49,445 INFO LinkNode.cs: 35 - Building node base_link -2022-01-29 04:01:49,446 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM -2022-01-29 04:01:49,447 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly -2022-01-29 04:01:49,448 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\Tests\URDF_Assembly\base.SLDPRT -2022-01-29 04:01:49,449 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link -2022-01-29 04:01:49,471 INFO SwAddin.cs: 344 - Showing property manager -2022-01-29 04:02:15,278 INFO ExportPropertyManager.cs: 422 - Configuration saved -2022-01-29 04:02:15,279 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:02:15,425 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:02:15,426 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:02:15,426 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:02:15,427 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:02:15,427 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:02:15,427 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:02:15,428 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:02:15,428 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:02:15,428 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:02:15,429 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:02:15,429 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:02:15,429 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:02:15,431 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:02:15,431 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:02:15,431 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:02:15,432 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:02:15,432 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:02:15,432 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:02:15,433 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:02:15,433 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:02:15,433 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:02:15,434 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:02:15,434 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:02:15,434 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:02:15,435 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:02:15,435 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:02:15,435 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:02:15,436 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:02:15,436 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:02:15,436 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:02:15,437 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:02:15,437 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:02:15,437 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:02:15,438 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:02:15,438 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:02:15,438 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:02:15,439 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:02:15,439 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:02:15,439 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:02:15,440 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:02:15,440 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:02:15,442 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:02:15,442 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:02:15,443 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:02:15,488 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:03:44,437 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:03:50,608 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM -2022-01-29 04:03:50,608 INFO SwAddin.cs: 299 - Save is required -2022-01-29 04:03:50,608 INFO SwAddin.cs: 313 - Saving assembly -2022-01-29 04:03:50,733 INFO SwAddin.cs: 316 - Opening property manager -2022-01-29 04:03:50,733 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:03:50,734 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:03:50,734 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:03:50,734 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:03:50,735 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:03:50,735 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:03:50,736 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:03:50,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:03:50,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:03:50,737 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:03:50,737 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:03:50,738 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:03:50,738 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:03:50,739 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:03:50,739 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:03:50,740 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:03:50,740 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:03:50,740 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:03:50,741 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:03:50,741 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:03:50,741 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:03:50,742 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:03:50,743 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:03:50,743 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:03:50,743 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:03:50,744 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:03:50,744 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:03:50,745 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:03:50,745 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:03:50,745 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:03:50,746 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:03:50,746 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:03:50,746 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:03:50,747 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:03:50,747 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:03:50,747 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:03:50,748 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:03:50,748 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:03:50,748 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:03:50,749 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:03:50,749 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:03:50,749 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:03:50,750 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:03:50,750 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:03:50,750 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:03:50,751 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:03:50,751 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:03:50,752 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:03:50,752 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:03:50,752 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:03:50,753 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:03:50,753 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:03:50,802 INFO SwAddin.cs: 339 - Loading config tree -2022-01-29 04:03:50,803 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:03:50,803 INFO LinkNode.cs: 35 - Building node base_link -2022-01-29 04:03:50,804 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM -2022-01-29 04:03:50,804 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly -2022-01-29 04:03:50,804 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\Tests\URDF_Assembly\base.SLDPRT -2022-01-29 04:03:50,805 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link -2022-01-29 04:03:50,813 INFO SwAddin.cs: 344 - Showing property manager -2022-01-29 04:03:55,199 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:04:02,915 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:04:06,718 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:04:08,432 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:07:25,776 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:07:36,624 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:08:34,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 -2022-01-29 04:09:06,042 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:09:28,401 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:09:33,716 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:10:26,057 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:10:32,832 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:01,760 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:10,262 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:32,320 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:50,721 INFO ExportPropertyManager.cs: 422 - Configuration saved -2022-01-29 04:11:50,723 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:11:50,809 INFO ExportHelperExtension.cs: 347 - Creating joint shoulderBase_link -2022-01-29 04:11:50,815 INFO ExportHelperExtension.cs: 1397 - Fixing components for base_link -2022-01-29 04:11:50,816 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:50,816 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:51,179 INFO : 0 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:51,183 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:51,183 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:51,184 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:53,156 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child shoulderBase_link failed -2022-01-29 04:11:53,162 INFO ExportHelperExtension.cs: 347 - Creating joint upperArm_link -2022-01-29 04:11:53,163 INFO ExportHelperExtension.cs: 1397 - Fixing components for shoulderBase_link -2022-01-29 04:11:53,163 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:53,163 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:53,164 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:53,382 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:53,383 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:53,383 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:53,383 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:53,384 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:11:55,357 WARN ExportHelperExtension.cs: 351 - Creating joint from parent shoulderBase_link to child upperArm_link failed -2022-01-29 04:11:55,362 INFO ExportHelperExtension.cs: 347 - Creating joint forarm_link -2022-01-29 04:11:55,362 INFO ExportHelperExtension.cs: 1397 - Fixing components for upperArm_link -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:55,607 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:55,607 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:55,607 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:55,608 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:55,608 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:11:55,608 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:11:57,637 WARN ExportHelperExtension.cs: 351 - Creating joint from parent upperArm_link to child forarm_link failed -2022-01-29 04:11:57,644 INFO ExportHelperExtension.cs: 347 - Creating joint wirstBase_link -2022-01-29 04:11:57,644 INFO ExportHelperExtension.cs: 1397 - Fixing components for forarm_link -2022-01-29 04:11:57,645 INFO ExportHelperExtension.cs: 1402 - Fixing 35 -2022-01-29 04:11:57,645 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:11:57,645 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:57,646 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:57,646 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:57,884 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:57,885 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:57,885 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:57,886 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:57,886 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 -2022-01-29 04:11:57,886 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:11:57,887 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:11:59,971 WARN ExportHelperExtension.cs: 351 - Creating joint from parent forarm_link to child wirstBase_link failed -2022-01-29 04:11:59,975 INFO ExportHelperExtension.cs: 347 - Creating joint wrist_link -2022-01-29 04:11:59,975 INFO ExportHelperExtension.cs: 1397 - Fixing components for wirstBase_link -2022-01-29 04:11:59,976 INFO ExportHelperExtension.cs: 1402 - Fixing 40 -2022-01-29 04:11:59,976 INFO ExportHelperExtension.cs: 1402 - Fixing 35 -2022-01-29 04:11:59,976 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:11:59,977 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:59,977 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:59,977 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:12:00,240 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:12:00,241 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:12:00,241 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:12:00,241 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:12:00,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 40 -2022-01-29 04:12:00,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 -2022-01-29 04:12:00,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:12:00,243 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:12:02,368 WARN ExportHelperExtension.cs: 351 - Creating joint from parent wirstBase_link to child wrist_link failed -2022-01-29 04:12:02,372 INFO ExportHelperExtension.cs: 347 - Creating joint manipulator_link -2022-01-29 04:12:02,373 INFO ExportHelperExtension.cs: 1397 - Fixing components for wrist_link -2022-01-29 04:12:02,373 INFO ExportHelperExtension.cs: 1402 - Fixing 39 -2022-01-29 04:12:02,373 INFO ExportHelperExtension.cs: 1402 - Fixing 40 -2022-01-29 04:12:02,374 INFO ExportHelperExtension.cs: 1402 - Fixing 35 -2022-01-29 04:12:02,374 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:12:02,374 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:12:02,375 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:12:02,375 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:12:02,655 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:12:02,655 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:12:02,656 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:12:02,656 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:12:02,698 INFO ExportHelperExtension.cs: 1352 - Unfixing component 39 -2022-01-29 04:12:02,699 INFO ExportHelperExtension.cs: 1352 - Unfixing component 40 -2022-01-29 04:12:02,699 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 -2022-01-29 04:12:02,699 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:12:02,700 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:12:04,927 WARN ExportHelperExtension.cs: 351 - Creating joint from parent wrist_link to child manipulator_link failed -2022-01-29 04:12:05,029 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:12:05,030 INFO ExportHelperExtension.cs: 1136 - Found 59 in ArmAssembly.SLDASM -2022-01-29 04:12:05,031 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:12:05,031 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:12:05,031 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:12:05,032 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:12:05,032 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:12:05,032 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:12:05,033 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:12:05,033 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:12:05,033 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:12:05,034 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:12:05,034 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:12:05,035 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:12:05,035 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:12:05,035 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:12:05,036 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:12:05,036 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:12:05,036 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:12:05,037 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:12:05,037 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:12:05,037 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:12:05,038 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:12:05,038 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:12:05,038 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:12:05,039 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:12:05,039 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:12:05,039 INFO ExportHelperExtension.cs: 1136 - Found 59 in ArmAssembly.SLDASM -2022-01-29 04:12:05,040 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:12:05,040 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:12:05,040 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:12:05,041 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:12:05,041 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:12:05,041 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:12:05,042 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:12:05,042 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:12:05,042 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:12:05,044 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:12:05,044 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:12:05,044 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:12:05,045 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:12:05,045 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:12:05,045 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:12:05,046 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:12:05,046 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:12:05,046 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:12:05,047 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:12:05,047 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:12:05,103 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:13:17,527 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2022-01-29 04:13:17,529 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruenametrueshoulderBase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueturntabletypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically GeneratelinktruenametrueupperArm_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueshouldertypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueforarm_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueelbowtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically GeneratelinktruenametruewirstBase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueforearm_rolltypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametruewrist_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_pitchtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametruemanipulator_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_rolltypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalsefalsesDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==falsefalsefalsesDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==falsefalsefalsesDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAfalsefalsefalsesDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==falsefalsefalsesDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==falsefalsefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:13:41,728 INFO AssemblyExportForm.cs: 309 - Saving URDF package to E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM -2022-01-29 04:13:41,730 INFO ExportHelper.cs: 147 - Beginning the export process -2022-01-29 04:13:41,731 INFO ExportHelper.cs: 153 - Creating package directories with name ArmAssembly.SLDASM and save path E:\Robotics\WR\Tests\URDF_Assembly -2022-01-29 04:13:46,142 ERROR AssemblyExportForm.cs: 126 - Exception encountered in Assembly export form -System.IO.IOException: Cannot create "E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM" because a file or directory with the same name already exists. - at System.IO.__Error.WinIOError(Int32 errorCode, String maybeFullPath) - at System.IO.Directory.InternalCreateDirectory(String fullPath, String path, Object dirSecurityObj, Boolean checkHost) - at System.IO.Directory.InternalCreateDirectoryHelper(String path, Boolean checkHost) - at SW2URDF.URDFExport.URDFPackage.CreateDirectories() in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\URDFPackage.cs:line 78 - at SW2URDF.URDFExport.ExportHelper.ExportRobot(Boolean exportSTL) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelper.cs:line 155 - at SW2URDF.UI.AssemblyExportForm.FinishExport(Boolean exportSTL) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\UI\AssemblyExportForm.cs:line 310 - at SW2URDF.UI.AssemblyExportForm.ButtonLinksFinishClick(Object sender, EventArgs e) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\UI\AssemblyExportForm.cs:line 243 - at System.Windows.Forms.Control.OnClick(EventArgs e) - at System.Windows.Forms.Button.OnClick(EventArgs e) - at System.Windows.Forms.Button.OnMouseUp(MouseEventArgs mevent) - at System.Windows.Forms.Control.WmMouseUp(Message& m, MouseButtons button, Int32 clicks) - at System.Windows.Forms.Control.WndProc(Message& m) - at System.Windows.Forms.ButtonBase.WndProc(Message& m) - at System.Windows.Forms.Button.WndProc(Message& m) - at System.Windows.Forms.NativeWindow.Callback(IntPtr hWnd, Int32 msg, IntPtr wparam, IntPtr lparam) -2022-01-29 04:13:53,196 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2022-01-29 04:13:53,197 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue1.035828411313638E-180.0156064900891439571.9357498027169635E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504418ixytrue8.6586155170563642E-21ixztrue-7.3748524136608228E-20iyytrue0.0044229329573873041iyztrue2.2771129801693437E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueshoulderBase_linkxyztrue-0.0122586821821900790.1285772495779757-0.0037054435004292684rpytrue000originfalsefalsevaluetrue0.99636680500272734massfalseixxtrue0.0065237009420894719ixytrue0.0010646616036528998ixztrue0.00028312700527736404iyytrue0.0050231810993567032iyztrue6.82113719161566E-05izztrue0.0086334538259584inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueturntabletypetruecontinuousxyztrue000.035865rpytrue1.57080-0.25129originfalsefalselinktruebase_linkparenttruelinktrueshoulderBase_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_turntableOrigin_turntablelinktruenametrueupperArm_linkxyztrue0.014397399905456463-3.2006162568792851E-050.27934838479492807rpytrue000originfalsefalsevaluetrue0.98521034391581119massfalseixxtrue0.023798222473833903ixytrue-8.87977733299251E-07ixztrue-0.0038853285623011904iyytrue0.029359472259760169iyztrue-7.1294436997127461E-06izztrue0.0062503483932010362inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueshouldertypetruecontinuousxyztrue00.180980.043071rpytrue-1.102100originfalsefalselinktrueshoulderBase_linkparenttruelinktrueupperArm_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_shoulderOrigin_shoulderlinktruenametrueforarm_linkxyztrue1.8457457784393227E-150.0550154986611603450.12015280303424725rpytrue000originfalsefalsevaluetrue0.51779610173045887massfalseixxtrue0.00404850874710771ixytrue2.1141942363467336E-18ixztrue-1.5487150407597627E-17iyytrue0.003755483293922739iyztrue-0.00037738536370652919izztrue0.00078832783822656164inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueelbowtypetruecontinuousxyztrue000.46634rpytrue2.493600originfalsefalselinktrueupperArm_linkparenttruelinktrueforarm_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_elbowOrigin_elbowlinktruenametruewirstBase_linkxyztrue-1.9428902930940239E-16-1.6653345369377348E-150.09870348455642336rpytrue000originfalsefalsevaluetrue0.30176308217533721massfalseixxtrue0.0021034428970283731ixytrue-2.7105054312137611E-19ixztrue-2.2497195079074217E-18iyytrue0.003050162507065583iyztrue1.8566962203814263E-18izztrue0.0010760910650178595inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueforearm_rolltypetruecontinuousxyztrue00.044450.2285rpytrue000originfalsefalselinktrueforarm_linkparenttruelinktruewirstBase_linkchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_forearm_rollOrigin_forearm_rolllinktruenametruewrist_linkxyztrue4.3021142204224816E-16-2.7755575615628914E-170rpytrue000originfalsefalsevaluetrue0.44770711794317625massfalseixxtrue0.00036770226690479489ixytrue1.7999450129153882E-19ixztrue-7.453889935837843E-19iyytrue0.00084342708626575322iyztrue-1.3552527156068805E-20izztrue0.00084474612356065992inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_pitchtypetruecontinuousxyztrue000.23716rpytrue-1.33300originfalsefalselinktruewirstBase_linkparenttruelinktruewrist_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_wrist_pitchOrigin_wrist_pitchlinktruenametruemanipulator_linkxyztrue-0.00073032374046050341-0.000899365669252000230.049056009995342265rpytrue000originfalsefalsevaluetrue0.39742022555481077massfalseixxtrue0.0015968430526387824ixytrue-3.0724322789165625E-06ixztrue2.5323557993615128E-05iyytrue0.0016343224414687998iyztrue5.0029229087463509E-05izztrue0.00025632256399428705inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_rolltypetruecontinuousxyztrue000rpytrue000.096862originfalsefalselinktruewrist_linkparenttruelinktruemanipulator_linkchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_wrist_rollOrigin_wrist_rolllinktruefalsesDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalsefalsesDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==falsefalsefalsesDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==falsefalsefalsesDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAfalsefalsefalsesDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==falsefalsefalsesDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==falsefalsefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:14:02,877 INFO AssemblyExportForm.cs: 309 - Saving URDF package to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM -2022-01-29 04:14:02,877 INFO ExportHelper.cs: 147 - Beginning the export process -2022-01-29 04:14:02,877 INFO ExportHelper.cs: 153 - Creating package directories with name ArmAssembly.SLDASM and save path E:\Robotics\WR\Tests\URDF_Assembly\URDF -2022-01-29 04:14:04,383 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\CMakeLists.txt -2022-01-29 04:14:04,384 INFO ExportHelper.cs: 166 - Creating joint names config at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\config\joint_names_ArmAssembly.SLDASM.yaml -2022-01-29 04:14:04,385 INFO ExportHelper.cs: 170 - Creating package.xml at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\package.xml -2022-01-29 04:14:04,385 INFO PackageXMLWriter.cs: 21 - Creating package.xml at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\package.xml -2022-01-29 04:14:04,389 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\launch\ -2022-01-29 04:14:04,391 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\launch\ -2022-01-29 04:14:04,392 INFO ExportHelper.cs: 187 - Saving existing STL preferences -2022-01-29 04:14:04,392 INFO ExportHelper.cs: 450 - Saving users preferences -2022-01-29 04:14:04,393 INFO ExportHelper.cs: 190 - Modifying STL preferences -2022-01-29 04:14:04,394 INFO ExportHelper.cs: 464 - Setting STL preferences -2022-01-29 04:14:04,397 INFO ExportHelper.cs: 196 - Found 0 hidden components -2022-01-29 04:14:04,398 INFO ExportHelper.cs: 197 - Hiding all components -2022-01-29 04:14:04,618 INFO ExportHelper.cs: 204 - Beginning individual files export -2022-01-29 04:14:04,622 INFO ExportHelper.cs: 270 - Exporting link: base_link -2022-01-29 04:14:04,623 INFO ExportHelper.cs: 272 - Link base_link has 1 children -2022-01-29 04:14:04,624 INFO ExportHelper.cs: 270 - Exporting link: shoulderBase_link -2022-01-29 04:14:04,624 INFO ExportHelper.cs: 272 - Link shoulderBase_link has 1 children -2022-01-29 04:14:04,625 INFO ExportHelper.cs: 270 - Exporting link: upperArm_link -2022-01-29 04:14:04,625 INFO ExportHelper.cs: 272 - Link upperArm_link has 1 children -2022-01-29 04:14:04,625 INFO ExportHelper.cs: 270 - Exporting link: forarm_link -2022-01-29 04:14:04,626 INFO ExportHelper.cs: 272 - Link forarm_link has 1 children -2022-01-29 04:14:04,626 INFO ExportHelper.cs: 270 - Exporting link: wirstBase_link -2022-01-29 04:14:04,627 INFO ExportHelper.cs: 272 - Link wirstBase_link has 1 children -2022-01-29 04:14:04,628 INFO ExportHelper.cs: 270 - Exporting link: wrist_link -2022-01-29 04:14:04,628 INFO ExportHelper.cs: 272 - Link wrist_link has 1 children -2022-01-29 04:14:04,629 INFO ExportHelper.cs: 270 - Exporting link: manipulator_link -2022-01-29 04:14:04,629 INFO ExportHelper.cs: 272 - Link manipulator_link has 0 children -2022-01-29 04:14:04,630 INFO ExportHelper.cs: 317 - manipulator_link: Exporting STL with coordinate frame Origin_wrist_roll -2022-01-29 04:14:04,631 INFO ExportHelper.cs: 322 - manipulator_link: Reference geometry name -2022-01-29 04:14:04,669 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\manipulator_link.STL -2022-01-29 04:14:04,785 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,785 INFO ExportHelper.cs: 317 - wrist_link: Exporting STL with coordinate frame Origin_wrist_pitch -2022-01-29 04:14:04,786 INFO ExportHelper.cs: 322 - wrist_link: Reference geometry name -2022-01-29 04:14:04,797 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\wrist_link.STL -2022-01-29 04:14:04,834 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,835 INFO ExportHelper.cs: 317 - wirstBase_link: Exporting STL with coordinate frame Origin_forearm_roll -2022-01-29 04:14:04,835 INFO ExportHelper.cs: 322 - wirstBase_link: Reference geometry name -2022-01-29 04:14:04,846 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\wirstBase_link.STL -2022-01-29 04:14:04,873 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,874 INFO ExportHelper.cs: 317 - forarm_link: Exporting STL with coordinate frame Origin_elbow -2022-01-29 04:14:04,874 INFO ExportHelper.cs: 322 - forarm_link: Reference geometry name -2022-01-29 04:14:04,932 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\forarm_link.STL -2022-01-29 04:14:04,986 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,987 INFO ExportHelper.cs: 317 - upperArm_link: Exporting STL with coordinate frame Origin_shoulder -2022-01-29 04:14:04,987 INFO ExportHelper.cs: 322 - upperArm_link: Reference geometry name -2022-01-29 04:14:05,001 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\upperArm_link.STL -2022-01-29 04:14:05,035 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:05,035 INFO ExportHelper.cs: 317 - shoulderBase_link: Exporting STL with coordinate frame Origin_turntable -2022-01-29 04:14:05,036 INFO ExportHelper.cs: 322 - shoulderBase_link: Reference geometry name -2022-01-29 04:14:05,111 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\shoulderBase_link.STL -2022-01-29 04:14:05,189 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:05,190 INFO ExportHelper.cs: 317 - base_link: Exporting STL with coordinate frame Origin_global -2022-01-29 04:14:05,191 INFO ExportHelper.cs: 322 - base_link: Reference geometry name -2022-01-29 04:14:05,235 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\base_link.STL -2022-01-29 04:14:05,274 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:05,275 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components -2022-01-29 04:14:05,465 INFO ExportHelper.cs: 145 - Resetting STL preferences -2022-01-29 04:14:05,466 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences -2022-01-29 04:14:05,466 INFO ExportHelper.cs: 228 - Writing URDF file to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\urdf\ArmAssembly.SLDASM.urdf -2022-01-29 04:14:05,470 INFO CSVImportExport.cs: 32 - Writing CSV file E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\urdf\ArmAssembly.SLDASM.csv -2022-01-29 04:14:05,493 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,494 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,495 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,495 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,495 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,496 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,496 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,497 INFO ExportHelper.cs: 234 - Copying log file -2022-01-29 04:14:05,497 INFO ExportHelper.cs: 439 - Copying C:\Users\Payton Jackson\sw2urdf_logs\sw2urdf.log to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\export.log diff --git a/src/arm_assembly/launch/display.launch b/src/arm_assembly/launch/display.launch deleted file mode 100644 index 96a2d12e..00000000 --- a/src/arm_assembly/launch/display.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - \ No newline at end of file diff --git a/src/arm_assembly/launch/gazebo.launch b/src/arm_assembly/launch/gazebo.launch deleted file mode 100644 index 57481cd1..00000000 --- a/src/arm_assembly/launch/gazebo.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - \ No newline at end of file diff --git a/src/arm_assembly/meshes/base_link.STL b/src/arm_assembly/meshes/base_link.STL deleted file mode 100644 index c298f6b589bed4d5547bebeb7d6d33a87c54cc6a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 11984 zcmb_hZHyjO8J#R7f~8vpexM12?E6wQYSI8kC_C>662%6M8d6AVqX{IG$|jbExRywz zu24%G(5%LfDzrO@3urV_qs`7cKxlw8SS++gBZd$(TKpgqu_k^!ANS0AX6Ig(AHIKj zy3aY!nYka&y?1Vw{eORdk#xVf^1a2LSKe0aU$?rPKkezf9^akIzZU~PHu2!zSHH3^ z|LE%d`Dq)U+M8A|3s^H{*$F50i)-$2}@6qkK!@avVIEzZ3DOC?8uHSa?!@0r}PH5=?+SS}tZ z1+#$N<1KIfPChlcwdg&zv*ZY{=AGHRqFi&z*xPgu)c@1TQ%wrX{)G$S-|cgJvc<4a|BrXL;AlOjjNP`S-|cgBeBNV z2}@NG+*ROE?0o^IVvf))=iT zR!gD^W&yiLmVLfP6%3I|Bh13z#bZLbU4=#>iuP00QWN{gCI7;sQgwKzO5RC4!kc## z%mUU-R^hZiYN?5RjsR=k&^MLzjd+Cq=qQ*4>>gp1)KU}s90At6VT@HW#(Gv0btHBa z%mQ|gFxqRWiG7X$Yu+$dDw!+dky0=V*ge9mt)(XRIRdPC!<-+=oEMLjf?2@s5voru zHL=eTV9h(T`Ocoy#G%wK@kl9{1>AUO-8B!60Bc_H)7l>1Bh=lFf?2>#Tj}~?ZN(8_ zeGh3jU86#Og!QANU>2}@NDt~dXnoERVC@g-e_dXvdX{_V4df})P0xLm1cj{Q7{YG zJ*2`FR1+8P;ZPs#?_PIf3XO1HV6Ao``>I`iRUW-?Z+`k$pI=b-^X{L`56{1YJq))M z$hBB;^1`k8lh1x~2?evzZknm>!4X!BU3_I;|Mj+r2P>F`{_lFon^$=AnPc-+Z`1p% z6@;m)TEv4RtXMYvKy||px9OU)=sj4$tnl|dsjvtu#-I6ab@K~*Cc6rLLwSkM<(~}D2%f*MlRhxP8ai*aD)}_`qK^7JGV?Pple{?^;5^tT3h{3XZVilneg5 z@Z$QrmryV(%*}{G`XEQINpI#@0i>Urok6Dun+PjpEyRHI;4@Tlb9?y9B=i?Bl0 z#2l+=^r=k2EZ%*z72GD=R-sl7x=+OsR$TDPtqb#aelOCxtY8+tYjiz0!U}zMSq&l{ ztYDUS>)9aw9<2!Sir-}NJsJhGqz(0K5P2$&utM5xGCp=$!7P~tdNzo7aD){ySMvBA zWCgQiHrw~aZhvru6;fmDD`!{15mrc*$dlEl$;B+m-OQWz*yRW-q}t`lD%#{?7SI32 zqtve;s6P5V33EliUt#y*=UUUO+GPrkup*4aa7txGXk9y#g}$*fAgkL?#gRn{I;FA) zD+D*J*Y{Mc4m}%AckICtR$%_?x5f5*u!32b&HBZ&t>8#_cKfEwnc51Dup+cV`0D%` z?_qOW`yBH|$3oj9JiGO6cys$wAl|z73AX@?JemkA!gvec09e5uoR`O2`>8m>3ar}t z{W7g!R(Pts`{tN~d=l2vZ)o-So7+4OUp8%pBSm^#S+0=RSg1<+ z!1iS`v|IeCv1I;hPNiIY(I09wk42@zVUjzOD7f-yHAZ>~#G1 zr{*~0C|~od2xDikCcL0!0xf>x;NI>e*CI> z`_8F8M}RdiPA~3}QZNhHJ;vr&)%U*tqWX&USM)gota)*IagUUOS-|eGV*5wxZ`^Wv zea^vNpCiDU7v~-KNGX^F>>lNF8|pPbdUiPetz$io0Bc^Hque80!jcw)MKdgG?y z8RvYl#}Q!7i?2q(BcWgxuzTp-$bNTeb@e~jPH+TR^Wv+Kd!!W10(Os=ul-#8@BMEc z+%r6Tjw8UD7bi>iNGX^F>>jf(ZK^+g(|v=t|Kz8090At6IDfiFO2I5(_c;3F_4Sxs zAB?S9UUCFj^WyyJ9w`O0fZgNJ^dI17k zSe*ar`jR8SnpbwRcCK}gl!95n?s4DlW5b{AxTfg;YfH%yV9kp&m3yQV%mQ|g_Y`*x z*Y3Hgc2}@NM$Hc zOE?0od8Mw{w;K0IDVPQ99#Y{7)I^Q|YhJ03_6^8AQVM1PyN6Wj0=1nZz?xU;ynQKh zkCcL0!0sU{PJuOwBfy$h)+_r`Bd}6x5TFVh&%`5A!-E6r>O2I7P;PKps z0(%CI0Bc^^KiG{~@JJ|_1?(QOlPR$G;Rvwim3@%itGP!?!7O0+kR4fpJsd}XHLvXF z>|V`1QVM1PyNB#73+zQX0<3vuUuw5Y?vYY33)nqmhdjWZnj^rPSN7L-yW}1z1+#$N zLw5QDoDDbvta;^}V7E)|ky0=V*gbG6(i00ufHg0leeB$oW#PUSk?xaZ+04lk6aG}D z2?}W+yM57!yocTPfE8D$8WC2=6WVpAT|N8XxMevwha3R$V`=BMkSV!Q{lxJ8sBzu>_;B>gk*;gCuHF2BfA>7SvHOm=VZ z+E2wSZV}BSzu>`p5#IYKW$CA41@F#OEx*WnFl%v(j1;`;^DaY^F8x%j;C+y) zW^s$S0194Tc|BLw(oe+--f^@&I2W_HMcN8p$#~`DOl<{6Six(1TEQ%Ck+y=@3|^zy TyRF~|D|i)6E11PCl4bt`R@fV) diff --git a/src/arm_assembly/meshes/forarm_link.STL b/src/arm_assembly/meshes/forarm_link.STL deleted file mode 100644 index fb511b3442ca5d1468b35914cc8edda55dd1078d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 19984 zcmb_kX^dt?6)lM)V-z$mnDB{g;yKl1Vpz~86=N|decJ~_&Z$5GF)w7CF ztK%Pj!0HX(Jue~dJK|OC3C}si^0<6PHAHu#YIdK|UjDG(&WD9h%+Lz8q71|r-gMaN zKYnv&;uu1x73DaBhyHFyd&%N98_VNnR6`jY#~yaX>i*;A62}littdy1t$*LyzU7|p zuZHmBk!mP|W8=0bto~=qA&FxMp;nY5$A7LoyS?M@-&qS``&U&%863C#`=HgmFT8aO zIfNmET2YQ1*FO3c?U#3MYD2hvNi~$=_l=Lad-9ptPmLqunAe@$?znVgd+NV7%&A5Z z=!Ki#@y!&~ZBKe>`-nFj-X3(%eY1*CEA&`<@TCc{>5TdItj$lgs199L4bk1GwqEqa zcFU7rVu+V7(+crY24e2a#mPy#o}M^{5Nbs^Wxn+%Yp*`@ZN_o_vT7)Ug4dh z?45-i!Z8B~wW1t3KKrhRu08l$A2N=smQ_PJ`n`E{#5qfeV+av~TJ3Q}=9rHh?Q#gJ zDG1{mmpqK47ok>^bFJoMt$v6++!r*I(|C-_cv!7^5mw!7MLBZV2sS?E3)f*h+zJ}X z;IQ!@qjzK7h7f8+IdWJhHr|N~yU|zKmv!Zs{mSDJVcp(Hw>ttFMOf$0mGk3Ck9X6h!+?Yov#Lm3=4&(D?hV+f&E zlp}|&IE}ASVe?2el)+)^)g0DZ$RP|N)QWQCu$8m%l{4Hjq6WS&np|IbJR)p$Ze(?K zc4!oV9xLnlsXyD^Y&m61^ZH9Zh8;jgsFm#o#${h})A`$))pL$*LO5!s&k7ON2;0dt zzLN>tu`kKKC<9@;nsK#TYPegX74lFk+eMABhl`opj;x70vUkq(S%ITQ*gkPS?h`M; z9xnT$4210&XR&{T?EA!Cgj!LKQH6yKGa+1OGw4F2V*r_Bpf$AJuplgwyi3*H>lFu# zCtH7Tb&6^Tp;o$QtT|Mpi1Eixo4o&-Ydsu_P%9k&(&8Tm5Y#B*%YQj#^5^qzz8{2I z9r@T}CMTTx%O1qOBYrUZw*!9T8jEC1KCE4ntM2GQs74XPc}yX4w#L0e?z+0FQNIr? z53?FGTaB>hP>mw2ZsWn~=K81=Je6}$`%0~B1jp=*VT5WFVLdkP?_EWxm7b4v=BiNy z&%t=sY94m3lL87QBjjPkdq^r-vdHeM0*g`%2ZUT zR@4ZGBUq6xhaEZEtS#m^9*in^@*JzaB6|ms^5_{s`jV(7kW)o^IH;LM*zaz=ejdh$ zQL7^CA}n4XIdCWfl|{tsBWM-Tu?xEhoCoGBcRQ=gbEO}_?yDnQkAnz{W)?mX70~_N zPL0M6IpyRY>M>UYts+{^58I91xoESG@AQEsjbf(yrMMB;Ew55l8Gt*WRz?!@6cOUUNQ zkK2gao#Q?PG{%t;lrhiWKLS>awwD7rU{%f>x_D8kQeb5vU>%SPjs}lzE&x zfGz?WMKHp2#S;1vYDJDbf}N<+2zusRub5w*x%whU8bQyzmm_NwVR9a)4u>MLm2vy= z-dbgi`dxQCGD5A$!Rj8k{Kt>%TD#{(@ALBM#urVs4umO+~s<(Mwq2{f+8UEI5;*hCJygiYSc=&y-RCEig#8K zka-*&7vLO3ty=Y^RxyuqZBQf9csK|BM!tgBzm&$@ITS$|9Eiq{o=1(KM*TwOar|Gc z27Ye|v!z+-eI~!7*E@@5O&=o7iL!FS3Oj)4>*moXue#LlKq0DfTz5;grXY4c;t#XS z7hlf%S2aiWrB?8SH7eyXg`h?e`=0Xp@gaX&?m?*LiFbTz{Jzt!$$8L|6?cF`5g$MQ zqVd^>+}OjR@v0S$;|_Fx9@HoTd}rMFi~B*S74o~~*}v^Um}WwaAtv-|QF+JoMwK;+ zum~rEnP-Grfup~=Y6T7%j{$`GQUvnrA9F>h6^;+~Zq_KmdTeE|cQc~4DxF{VmHEvh zh2GtE-d#Rw7S#jj5=Gz%#4FFayJyU6U&RWUv)}5dYE3~PCq_7oP%G4p{bq=Ir|-4G zECW7{0iuP>9a(i%lr?>b)Vp#o1HPCc<;16R$rOS;I*s6cc;r#8=wYP@TJd={cB!mV)Jxbt4L&Le4Xhjx{_rNrl>C>+-Hs+mUEnE3v2eFUw$rNFJ%W#*xQd5f-8E5d~3dl@YW;RO~lF zBo1m)=I$4A;`86@%oRbal=(on>zJpy`8khh7-h{t4g4ws72$clF2bz_qDq-tR32~Q z$Oyg5nK*h7v;vyvzgIWjZ@2xTW#%1?wTLoePjcz@hzJFNjES%)ePuw^Aqz)Bn5Flp z`h{#`9tejcs@bRFFw2}r;=?r+>NH)e zQeD@;N)d@W_U?3bGlEu$qdbYLqC&@U1Qo#!?N(P2v;qf4uy;WW%lVoD2GPKX9~M?v#AII26T z%)=41lJRhk8j-47Az~h754Tb82y;AARAnteG|a0;P@{e!^SJ%LaIfAe^0N}Y)GFn% zg1ov2%fmH_fXw6Is_tJQkBp$4#$&~P_gd8mV|I=Dh0NpNsP4mIJTiiE%%kk#YJ~Y) zfgkl7`3j=CpNPK72+ER&>uN-b#3J*4&1fD6e|2A!c{qYrG9K=sMx=^Xh{#v=i3jQ( zVU9PoFp$N6oXzN;`OBgS|BtY!u zDIc#9s!@b~Lotj{D~+~;$W>H?ehV^;sIAHuDqRG-8j)ZJfXwYI@bB)rBd8ihVEl=8 zj(p#T@1f%TZ@%{mnQzc`-wS89(6G9Y+0$KwY7}98EZ=`vm*l7vp;r9rqRYW|Xra-Z z_#S#MB7bYCh~doDms;^%?kxITxXb)4$Hsx^g=o!{k9gj#98)f`&g5cc|e^YE+VR3mClLGZozZd8g; zE9)5lrlE^ajUt9eP!VdyZx6a0I#OH>qE)GMow<&hBJ6zhRiewG2(_}Y@s**AP>mvN z1bsE=B5cg_7d%|sVWm~C^H7Z<_-=idLlJ6a$NgKGE<$G+euD)o?a(?Z)hL2rS9LiQ zp;ny1y9m`NLTgw@r3kgMD)@IgT@KYKLTl(8c@M|g8EcX4eeye^M0eLH)hGfo_g%vr zism?VIaH$v)@^-+T5&WZ;+~scJimJAjy8lFtODiv8J>CJ>D%+Zc-b7~c!%Zo=N{ZV zwW3@&_F9EQc>9uSC^HW{A1)ky2t-9I z%8_H6)#_HOu)RSyQVnJJMcwdxFmenb)QWQC_=Wj@w(;2gh8fjRhF^?7o?1qZA%t2{ zjvT2IjpJ)Gs-YbHe%qhEMtKMkf?Ad5sv#I+&AQzaYvb?l9YhWr^In8nQH~te z?X7p>=Hq8nLm7UpkNxe0$T5UaE6Rn#&p~_RNi~$22i{aD9DN8xMJvjY!)Auo=aO*k zl4>Z!FX~q2t09D1QH~ro!?ivqhPPtA%I`){1_#EUGpf&ty$H3U963_&wswAC-p%hu zP>%K4?QaW3c?e;DokXn4obTsH?`oh3>lAAmKc>@J7WwutD#n9 zjv7KB68cgEs!;fpLlL!AIp^yOhlV(&y8Gd;c9yx{(YDGD6{CfPx`7QfDU>r*` zs-YbH>R0hY2<%bHxAW!dJ_JLoMUES7C!?BzFh2Pzeh8sflyj}xSgQ&0$airlBM+;a z{5=4xRWCxVDCaS6eayFCfbno&&`<`4jlcYr0vq#Qgj!LK9M*}g_wK@`8P!k*hxM`i zwS^&sT2YQ1c1E>+4u*wA)lde9osaTYBZd%aMLBZV%+UH=5}t+gJm0OM3=Uq`LiX9G L7ok>^BgcOM>&LBF diff --git a/src/arm_assembly/meshes/manipulator_link.STL b/src/arm_assembly/meshes/manipulator_link.STL deleted file mode 100644 index 6bbdfa566555fda5fe5874ca1470c094b41bbe78..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 54284 zcmb__3A7c(wRRa3ClpZ#D(Dpv4wEv-Rngn$G&oNXj1x{zoDlOH6-2;@fU^-biN5Eo zQG!Qq2o4d^aQmD_9vBi)uZjkYW8(B2;)MJfMc&?3dv||zx*Pr1`rlfvw{!OX>f2Sj zYFBmN-i0y$fB!G|A-6X(G>b>}GiG_Isq6c}xKX!67hmv6ndM#EpH5`{{okXOl=Bg+ zX+$u3$8%;YqMbRGCLD-hD@MnYZfeWtP>pgZV&Uya2fzXSK!jQ;2lp@A4@PLu5y5hT zh-s`^X{@T$Rs@Jht@QU@o_xY_WDu-jD?})t^(r>)%&|1#K!o%>;&=cDAXK9qitys$ zd4&kIVl@Ar-*eTl6(U$x#L}uUO(mXR2fei*X$#v`bS}cq2G)?3C+oQJSfw0nrR*%L zhs2%88H5)DjV61mau$IcDr5hA1ZvR3Vy_T^R{VRuSEy+~B;%I#O50+D%H&}(B0d5& z4TvB=9)0HCADnRNyLNS6zv}j&d(Zc+eC?4p1XB-tCt0;=1oxi*NOa!hWmYrn!g>;u1O zdGUeUY+IfCx7w(2W*E_B=V0NuD2D?zh@epq^5cR1z&PU=`d*<15frCD<5Y}5t75NE zg9w@>fzBA80}*J2BjO`ag9w_H1ssS#s}6tLHMnXcH;;V|jNr;M#<#SOzdRF7AAwOr z#JF{LEqdAaFh7 z3Z^)HkIaCG;&qN~p;hsULJcBl6-1i({CFS&t#CE_2%HT#OL+Did*?rM#tJovFsHQy ztAcgkfj}#sZ{7QET+YVa(?Gk|{BEOQ@WY+H1A$gNE1O1k%t4?A5eIC!Ps=Hfcl!Hjm= z%9=5<2-F|~`FyWXgNRe!{c&yX3;S8VVgyd1eqI}K_fA%$Cjhp3`mZ|%H~oJ590Y0*p=XpV2O`jlybAKYLMz%o>XQ5qj>*dW8tIqA?6~zWMPuV8H{yriV_m>tOzN~_qF8E$`d2C+r;p*`Bsb|bYg|G(np{M5!8<;zaNM|tKS^Y7nuex+EI@>a6cVfYq~a zeHNYn$?_ZowiR#kY;^Te*IKJ$1Zogb*?)C3r}^?64n%lXcXzDaG3=@wgaHjA`uyPa zsK>$Qe+L4su6?0fZJUEXY|G9>)F5K~r>{l-JodO84n&|;@g9X5M7-Q(b@bj*BXT$p zfmV1j@Mj|CTFQ_1DV}>m8t!M=Y`I*7fK)aMN%K6y`5okqgKFH4us6j;W+(iUh70+GN zAOhElA9F;Y6|Ng&-alwc_~GSORE&AN)Y`ed#h80~)Bg`jLl?BPb{{qOdu7=czG69;?5o>7nHpax`WcQ|`$JuF7}Rz?wyqwY9PpubU| zCT*Aa+R}cISGfqZ0+~2yoMJat3#zCAnMb#c{A?MJ zm{*8ED~Vu^SExb6^ZU29oZGdM!+{9jD&4952;#2qBRbKJHadp`5yqreWX)?ZzaOAU z5yaP4*pCE(R@8nQ_c3>L6AdD0+@ivGBnY&^Y-h|KfL%|AY{ml~AKH`;O5pMxd3-j$_p$Cx`3TuczJM))Hz|W)7T{#uOpY zN@d5f?$+ty)}3FXclAq4s8N|YaNQVFgg`5m9mj;J7laq>eYf2?QKK?*;F>q42!U2A zJC3MQ2}?%|pc6nuyR*wUtWlXcFn5t%0RpX5b{u~R+bd14olP89l~AKHb6^fOrU-#n zDmxCdvn5&eH!pPWUD5NM^c(agSW!id%FID)B{^%^^^uD}E0rAwt=ibF^A%OpsLUL+<{`rsA<#-?$3gijcKK>{ z6*Vd|2jwov)I|uiQrU4(7OlH1dSDebDl-S}B{uKoB7Cbf9~Wn8L=a!W&Z$=H@8nHC zYWwxiKG8gHd+z#y=Mwe35wUNtaZx?|yG8qZEh5lLM>@+vbIG1@SVMD{cjGpe55Mx= z;E6j1MOlPq1J)2nK%Q7DT3zu(|B80=DeGWwUR%vW}1dgJ}c75Qe`v}w^g636}zoHOpyCbu|Xoa!yIYeXUk07jEoUc%W2=UOOeGWvR6|NN@ff_`} zNat`M0HUcpsMPUL$<>m$)1LgbtbmxHiY6sKg=eGb%MyW(w5&k=!E z7#m}*8FGJlS<`Oev10;yURzn6QQy5hq0`Pa9G^RmECrkWv9JBzm|y?v!is6?X%VPF z1dcSF*adMMaUcS%#!kC8c;at62**R;EUg^+aL14ls6hnA-u&)*4VZ}|h^ z_~V~93d7Iet}q8`5aEy2!-N=~gFvgU>pGT?IdfUSV`$9Kt9A&NmF~41s6hnA#+c>; z1X?vs>RBEzVX|=CF{W=g@vGjJ12u@i8Dk71F33Tk)zDw;RzB+5`&(Q;&OB}R&@^w= zkH-o%h!EMX6=N)7a3R84NlR^xL;6t%4y(a-rB9K|KGKg20Eg9uqG%Hh^W z27y+x(uCuBTD9wU>S+S%;kb+t8#VQeIhP;;tz`WR$5hHbPd4pl5vW0gF+WO9 zvc_EP@>K@mTMg<%c}zH_47tBX8P4{@7}TWg5+6VBNIxhiT7=7qDFUs?+lX?aa8ORH zQ%+Q`5)C3~-1wh;pKEP|WL;6Ez-*1`!m0IQvje%tfFT&8vuV zqHs`7jCJm!1`#xm;S5J}H>R9u=Pn}9idI35a$>p$W6Fs-+Y=2UXg$JNlyYJ&0Pv;qU0;eaIv{!^H#}Mi3SlO+r8c9 z#MsO%L|7}~ki0AXr~rr6V7t<%Ajyf`j|>8>WJH1_C&rW$Edn)&kk|+Z<;0kBVg`X$ z5_93;S)zL_Y7ilFOgLm-Sq?;?mCUztk`wEc6GO>~Jgcn+5wcd4!>x}D0%)J=+;W zInkc_c&zZ$hX~?>=jd*;ZmF;7-8+8bnC2Ms(wQ@EjK==DL+!_h4XWw4kt`cCfbD_JjDyKYvr-ct~@M8br_+N%qT3huHMP zE#uO|U)6syW%n30i12gby{~tQKOXY;`tQazdkD0;$JX+tp zZ*zIHG=80EUgY9Y!g+pw)t~oyZ z{5>k~O&JuU1`#rDl6U)z8W8u{VM1l~dCeXItt3u?<5>OIp7HtrnqB$Lw?j38R)dID zQg7lApHAu(Uw_XZDpLmzj!}aMnPcMBFVEgCK4$vz%Hb26Jp@|GoEEQ!Y`R5!_hlbd zp8ss9&UULo1by9VD`K2iuT0t^e(tAVRDSl=;21TCko72e_ng|AdbhrtgaaovdkD0W z^)Fs^Yk#hO)IYj}m%lSqGlSJ2LMs;}f_pw!KYiAA;g^3K5~BtYxUU$~?X`LJ1#5N= zXI*}GJMXd%ATDjm5Uw(RN{k9_qg!}$wj~F$Gz@5mL z5yOVmo4O7TPnz89A<*itZ+4C1&36#5p83;*wX@%C4o9pQ8lwgg#yp?Ae=z1fLYza0 zas$G*T43vRTtA-s(}QJ2(AQ3&N!ukpc$e`OA;ybWh(IgyHc0#Nr}CwhwWs$Fhm%({ zKFK=^ia|j8pzST9joD`2<&|mM4G0H6v`35@M9`?)x+2#P8r_PHE+Wv%_iE5tn}y>Z z{Is$kc|~(6dCNhwJ$V~JE2>QUhs@nEv$qWI{`S+#N8<+bib^#4jW~OPEg3`WqoV5r zHHe_~5zx*l9D8l?Y~>eU{WuI8yh1A+Lu2-uxUw>Tao6y|8-{qJiwLbya$`m7qoV5r z+d?ZGX=6V7cyRdign<=~Amym!O$uevN4#glBu6Pdhc*$$DWlAn+)XrBhl!0 z=3rL^k@?dPHH=hzln;as5eF0H|zJ@{#zXSNycLh>!>h$6GY7x{YnM5kv%9VKnIt z$%5YD_4m~4rytZ`*N5!~BJ_KDH&%2`4E3DowI$!svlY$-Vwc{h%&dQSE zYL4T9Z_laRcE&#O$RkR;e{e>&8m)q0D{P5&&RMrq;E9DZwQUy>k{N_!PnWM^$n6$^ zRv1lVF73CX(tS*?`1ooc&AS9(DO${pFglIw8FVSe+4-H?L z7`<(~ZLiwz&e$`4=n#4~fVXNsV%I)YMJuB#yK~I@IU!*hvaYQn*7A)4kGKSvA4X_KRRi#a#k zbl3lgP=g3PKQgy5$NuEAdbcZ1C5{`bh(IfqT|bVP)H#0mfFlV}t)fO{ZkJ{vKM4m8 z@#KWA@w{z*65c-Vw-IU(p=WL9RnwKb#oc!;6UReUM4*+*j^o6w_ls{{TOveMMUBeb zE@dKq5*DwP3_dU(wac#IjdPxgP=g44E^%J{andnyr=zwaj^$NEpq0wbs{tRM5%0ar z+w`^J$|`D9=5{H=@sqH4RlVk{c&~R?SB8E4S%exy=rf%2>a}ST;txM=C64wgBG5`@ z=T(OCD=rZ|5ipRg`lS|bri$E)tomUISOpY%)Xci$BR8gZcw=1JAJLfA0ToAAQ@!j>N+e@AX z5&9m*d9~gA{}WI7=+DG)r$*4VmDa)56ydzO;k}dNtq)yKi2tm58bHVl6|V+3n)%8d^;=h8 zKnODjH7awvxbIT&*eTQNH_o3DZ+!fIo(2)Ri#o5K-MFRx=Z7yQj={aLEwobEd3EKj zGiwh_pFxNPy-}mGYd76@$@?Co`i**YMts<%`_pccY7jxP*1?huag-fLN2*=&5Q&u{ zoLA%KuC2^DW-NJibBTJZRk1aShgPp9vO^sCyG_Di$(Z=o<#Rj@#fG1@ZJes(LU%ud;WpVf5*Yeg=_gVuTI*7@=ht-C~%hj1JhR|bU- z-9>LYsh$%NDzg>F#+Vm=wRgDRq#^Oa@BEjiK?G%nRG=dsOK5sFfZ<(QM`Q$V8gpxK`M!S9aG& zZ;he-Jaqf{(h_RKD-YqkqWwIS{oF$+nys);be_ECtWeKBbl%as1=RO|5$LTkboL3| z*=J4(HPTxT;k=@=Pw37*4|xbhgIBgs#?U!2)N>-84fQq~T~U?;y`@|->6p-+6R#+t zMrMYGa9+_lF?8p|J3WM=*$Vq)44tV%JyX*;T5tZ*HwBghy`>vcuiPzkXX;@k)X0kR z5Y8()Q-|(MJ;p;Qnys);#?bReMV~+DnM3b9;$1X(%Zc9F=Z}he{#e`_HF*f<6+M51 z?)k%%5TP<#VV{iY`pVkcfS%JsGqYD!_Ca}GS_JQU@yUx2Ws5MsrrIUcqzK8u(h@!0 zRrKi&5om=YVxJ%@?g{dqIjG4)xSrGVV8uNTzR?R2Dzg=ioBa}y_Shz>J?H9|v>%Fa z`%)*eSv<$dbTUp56lc9FtVW}&_aaf|EJC0L5yYo=BoP`p5aC;;-uej2AIa&SR;}JB z_C38q1g$Q;|7-(Zp%spZ?-lK2_Aj}16yX$({qqr?1`w3B_0F0Nc!gFtB0dM54fHOp zRZrCfd@;?`*(3^_HN=7$_!`Gw;tr5t2g$T5g zxsbzw8boNVLzV*(Xod6GpSw7hv=WWm6>llJ*?E=DI7DbQ*MsJ7qZ#p_NZ;MgJwM*^eM< z5J7oGD{>pWLIhgjn)ho)jTvj#1br78;EGb2f47zQN$o3YROWu*nlDD6mCB9-D{@hz zGIRL-C_%8mnTkx`>EbKto7wa9A4ZK0LQjsq*CQKK?*U^H#5eo}?4R@@d^sq8qg z(i=4@GY8H}zcyU0xGl6&*>PaSI%-sA4qRQfRzIn6S1WD{tyFd#4VCv=A=!v%k-J`a zw)@rnh)Ar6!^%lNDthMtYE+i7vQ@t<`*#kg6}LrwN~~0N9C#A~YEfeg@ zWq9qHRw_FVyjuh{Ds#J(yR^pLWw_)v61C#C&`M>;fj6F@MrG%FdVcUL z@72n+g;r@kF3!|=lA)Fg&R3Y*;XCc5PmUXRXY>jY^yRu%PVyRrr#nQT6^>yBp*IBt z@U=R%i#Y7imgX3;(eBG8I5YDBA-YknFyG!L={vl@*8R{(QuP6GnlmEKxUiaAh& z2pPAWejoy^FtUEnQG*DHW`55bXNk4K`1>5Va~ktaN$#0Q_V(;pVayRBb2q2wh(Ifh zzwedq$jnYwdhZ8&1!o3aAE-fufA=jmfS5lYC6>c5^t>`;Ttz#n&sY|s8)F6UJn(I=9L+Vm92(+Sa zBejB$IHWF>s{#2t%S3|+8fmUe6%ME$^blx8-@|hCDOaTs2Uj&ptv-Lhn`jV0vEjN@ z;gGsi>lGrCx>VtSdQSefHqju0Vy^e%(E5a zxGt5ybxt&h5LtEuix^ypuvXF%fBj7y(vLcDSPix-eTrQ6k$z+lXeIsQuZ<-hQme0H zWi^P9*a(NzrCJVb3#}wh!Xb637J(W>$Q%<6nO7METFDIMFHfl-ygsB>UuUA#AVSuP za-?B{t}(-i3Sn09^qUf_m^Z4Xhmz2t8RpYG6UaVViBl8 z1mzXIhsWhazP}`cKr5-)kbGrtBe`O8zQ084KQvz@?FzcZ$%&!V>T7L=)gVG*BOG#niRHky&`M%196U=xcgu~| zu~-cvWR3}k%qz=*ZK0LSw{nsb`TmlSdyX1J$XZd3^nM=?fmX5xg+uNyu^gyDgsget zko!wQ$%(vbZChw1>t8tJ{t}Bo4I=O@MRI>h2H{(!XFHn{?WvE)3Qv8AAU?joMEU`h zFCpe7_y)49f3K%+O(>U8t$syn^*sbyVdkTp_)1)nTKy2)MLzv&xZ|K&{fgA;hp0gW zW+hvzueCBB0W5ORAEE{k`uBS071ip8QmY@L1`&Qvgc>XlfmZPCAbCZ# z`k~b7hp0h>es|!!qFVh>YV||ZAOdrxt<~2WEDwQJ@a-UZMYZ~&)ar+*L4LJhyz8xg5s8&CeT78}E)+W8R7 z1nw)gR$pt8Jp@|8cYWj))#_KIR$sFye}`B`gnpyryrNqDiqz_ds6hnoM7CC6tI0hC zTEVx9E1_tT-7Ksr&|4* z)arW(v?6c0Cen_ftun1ktv>H+$vX>*f!5lU5p8Sr>r$&9q6QKAb)$<1+=SpE(8~9U zYV~8O)emVdCGRq5wkPi#Xhms-8;up!>c>*6&nqg?&|1+OFUr`Gt<~4NEIbZG(E8BY zKH{KS{kqiZdkD0`F|@V%b*a_&Mi&vZZtT~lZmi%g3lD)-IMTLOKbBhkkaAS=zJ#)9 z@?L{7wN|)MKd4qemRfzz)QN_2u>Hc6J;9c2t-juo;&C8?@~+nQ5eL=k$5N~BA0Xksnrirg9ysU_A6F5R&Ym(hd?Ww3$|82mRkK##;1)>+tS;JW#Nk)2i5AwQmfDV z2lvowXm7V)uCf)jWNY>H?j4T<5i;s+j)Q9TW2)6}rJ8CFfmRqzW2ja?mRfy9=#I?M zwC&P9uebG3JmBsf4}n%V7i_J5EVcSNx^{eI71emGWFE^{QLTO~wfek&@XE0oIy36c zPi2X$ZOPW^>zz&>2O=bb!a=qAvDE5&2(-dz+FE_Od&k!5>rAxlh@kVM{r5RtJm5|z z4}n%V7m_T>wfeeh?f6K3w6bKln&Y5a{kqiZ^KPJ3>io=Mze8p#$t4zTYxVVZF^>Zg zk{N`9YV|o^ajm|GKr4)%4y?8bs)K&(15V)h|n}zK8Iw`og<2s?{$`tv>CXsm4ci z(^`F6QL;O8t-gn#NF`Pne_N|xlUjY<2Q{_{LciH|{eW8vJOo?y3YNd8rBZdb-l zP5@BN(W0j%`a-$E%AG#=cU!BUsmPzR}A>5i;5k!5{1 z;Jm^*Nb$-d&`M?JRbCw=Yt)L{l~I?S6KY014I=bCit`FQLTO`wfde0 z5&C}4d4)B+*cMu;?7X5{{m|9w-=0+cvPP}AUCDg1pHr=VMQZgu4I*?$bzWhmH@1aV zDm$;JR=?tE^~WWZ-mFn8ZWs4mTdQA@T76H02;D`US6JzdZK0LQ&MW-xRrfw_OJ%lF zgyZQ@@ zt$yrk^@k;QaxjOY*$QK0YxQHP)%P@rpw*l_$=F)`_y{mdpevQop-d3R(%f`f!^9${p6k^)JShVg!3xzo+9>2(cqQsldaX)JDmbL8*25kt|-fa z-r8FIbm@MUBeb?wYR`21ic0S~!XjXr;2_n0Cv8`d72g zBMx&PYE-ry)g{63S7!-FAp)${i0nApZ~LZvTZic}6%LnBqcU^En>-s_eblwWQG`G% zl^w^4gSQPY>GMzh>G+!Suv^z`tw4?m!ouPC8LW#;Jf zgV%!|2cIt-MF_M~*>UW!enxozJM(BYwUSx1`KjT5 z&Htpr|8g&CRA!EsyQ~i0J8Fb*6d}+`Wyi7PtF6P9`A3EHR=hWARA!D-mOT?3J#wgU z6d}+`WydjV|98tToJ6;gnCtFCjmpe%m-anlA1M-c+8RCXMPzi~-;@Vy(;SS>A~ zMrG#c+`lzgc>B?TkC<@STZ2)9h^eD~8{Bll!hq4nFvmfbV{r))Xr;2_`1qE%a^<+6 z(`>)2gc_B(-C-Bb3tk%0CLBcwv{Kn|?0DM2;qAZaK^%)qs8N|Y_MZPpaNgu)!cl}k zE0rC`?I%wQdw)EDR@BN8YE)*9iElg_9CGUO!cl}kE0rC`%EKpw^L{jsA~?5%8kL!2 z?Tm+mE^V&~M-c+8RCXLazUdntKXN$D#9<}WsLULF=H4HiaO%6lQG`G%l^w@FdLCC9 zeW?3az)_e1XB-tM>vWQ zXr;2_`0rPT#f!TRA&$jW)TqoHokv_5Y`^jq;V43&mCBA|X?;q3!k05C=IvF~sLUMQ z)?6Aq)w^9diV$d}vg4pLLo0oSMg4gHKGHbnX@*&`M>;L9@N$*2nN(s8N|YXstx)8Z1JfmCBBTR&Cv_ z^MiN|+O}AuGIP+HkJ4OHgg`5m9S3Ef*yXDQRn(}=9F)7FG$$4z&`M>;L0L3*d3RM6 zH7YX)<=`mI?L`Q*QrU6PZV0=T}jqGIP+L z7^Qn{5dy7Lb{w=j*WG^J=|0q`%pA10N9mcN2!U2AI}SQ!#O{>QUPX<{%t5D*$UDiz zeD)dRPBMuG5p=4F((@H_xYH8lU1$rfRCZp`iL7SNa5H;WQKK?@Md!IFJtr0+&`M>; zK_|=DokeF?QKK?*(77~9&$~qkv{Kn|&;K~G+>dsgdI zMUBeLLCKKr59U2R%X7>@%mit~Y8_W)6D(jMC@YA_Q8g>^SI2xZ<9jr}J~I zZHqN3TaK?6M(Oi;Ap)%E$=f0v2R+e;?j6A6CDf?Q9P~aQO5ZaSA<#-?$3gEhLia9X zWeGJZGl#wjVVS)R3HGb`7rDsNIuYJOokWcK~X|8kHH%EiD`u zNoL4HpcTrFBby@^p?J{EafnT(|_`q$}Lt}~%Xr;2_c;K9E!Y&W; z8_0V~s8N|YR-Q4wrG5P6!cl}kE0rBb2X~upY#!=WLXFDIF>c*mi=I3A65%L9pq0vw z<1aTnTHohnek1(G9Mq`H9E*A_Y8!d;b;41EKr59U$C-DB@z0jb{zjrG2i#(^N3@n zjR#w?MyW2((h!arCCS+n?`_rnj}IQJFb-9yg8bC>%uyv{Kn|JVI-5 zn+JbN9Glto!ELcdt(b$?WB2|W3r7(GtyFd#70M;UKKY0uc&lCK+!kxpia9Xz8B>Hn zE0rBbUKVAIS}_OBF`H2x!k&3d6WusHGgM91lbO|Ywih9I4yYCLajxW+?EXRbUpo$t znr0au-88GEXdi*?B7(;)&AaFoBG9VXtHyPg=8x~=6|X2oU?wW=2U_8X_z0ZgxT3Is zJ_0p}z%^ftKr0*(AAxfT=Pq*l2-F|~S649tt#CvvBDpD@p3m&x0eM!_^Pv5E9m`E! z-w$?ee>zHLdxFS&&mf58jfKxaZ6z9g&%g+MACTqHCsWqw6QpwFd&L~8L4-aVW;qan zR>eI>4I=c}Fqb14MYPfoTb0`9>a4z^9G?(n(8o4d}J06XQ{X1ut12u@Cegyerh2u`KvELVP zyBH_mE7Tx@;%~nk$a;kcv|_JxM0^g^AcAJ4{c<47;UT~Z*T2t!*?{6<|H{toVoN>( zHHe`2+rOW0*ekT+mh$6)8br`Mwtqj*=g_v$3g-g#1OB>19LdU2`Qi&cX?Rw5iqZE5E5rZSlMxmKJUcPbR5)g z*6NL8=7=ZV)b{UDOUj@0A5do59RIQPYTT$>BL1Cj_-sI^1`#at?~JB@oNEj{*-h); zI_CXt;s@uRUt>*t-c}WsnS*8Gj`;Uoo_wMKftp4Hqa6Yx$OzWxSg94F{RpD(d84q| zc|GXNiX4hy4I)%#ZXdDR#L3pH!`C-e{_~U@tUTkTohw^Szst%mUcE~L$7e_O3)uIb zL66D@oLM4*-ae#UfrLWcE$8blP2E+WwCptly-eq`f;vq9yjPw#AJqRt+_AJlH7 z8blDc{XN?cM4%OUm9#`0-;R{OhJSb;#^d~v*I3{COxoFtjgP<>AfoNi6D_*_@1}+b zA_A>&zWF`J`Ln~p`|iu55KSBKJ-tE%f78V1*AE}eUO~^%E3~5D+Zd5M+d-4IOMHve zL%$!`7FtpNY)jeoff`y-)=JhOaARgb4n)xC+L-fdF7^toUjLtw7V&k@of{CS!MuXp z#Ts5l_ z8O|DB2fRL5<`u;&jpZcoCJ1I{4Rff>zO%RdJ7)>v_;#cqKJ1MeMDQ3gBAL4h2S<=K z99xb#%RDoR5vV}~&oM^xtn_=12(;ok&4^^SCth*pWR0ExSjH1Tl0`EJ)^Mg)gv!az zxj_V5VPyS&=;$_{6ZCh92b_IS!#S9};&Xz^*?#09*h-_BI}>fYtig6Uw=-XsgR>}W zc-$!-R@VKTf6vYmilDV(4I(K1Hcm+{Nk$iA%NdT_l}v48p39MF5JCSIcZtzSrWTG5 zd*i%9EA-Znpsz{WCBA*t!(s$l;TZY|&T8BipRaIr@mY(1=d+fNKn)`N{!wmEMi&ui z#o3NIvbh8`h|qbJtj{8h zkX+J$P)#0!(Z=+8bcfh%|M}dWj~@|ooSB2ynj*Me{+(NLYp@Za8bq+H+%$LjZ}ajF znIoti$j85HOId_!8W6r$q3Qc|U+xD-kU2OzBOgZA_S{1-M*=Gh`^IYBZASA+hLZd z6|V!8nS*8KkoD1kP)#1f&E4JYy!v`>_s5TjdEGHPXBkCsySN^WX+$tbBf|G;%e6a& zX0w0yy?N519tXCICntIkEy!5njFAJ|_4mOd1X{7o-nvuYZm~k?z_emA<&9t z=HL?t-MQR!No?8=Z=Ez`hdOEyf#-)}gm3i*JV6piXf`>#A9LVSBmXPyJkor6A-?1s zWI1vXXvK2c59)bnb{^J`#|kxwpmDQVG#TAo1X{72#)Bdlnnhjuam-PJ2#UYua3}pD z1X{7o91cM(B*yKjAJ*$m&Z&-y!O#Hc|8o(3r=79h|HpNi@3wmGeJ)9L!T9j=`a zqXrRp8Z1Vj70cWYcNV>TMgQ3J=+Ju7!<85{h@c#7MSc7xD#axtf@ tZ#A-KBv$-8N7n68jR@6XyU53KIL$`S|frviV)7L{{>(J7XAPL diff --git a/src/arm_assembly/meshes/shoulderBase_link.STL b/src/arm_assembly/meshes/shoulderBase_link.STL deleted file mode 100644 index bad98d04de53b49ce43712a08b7c6213f7d6b192..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 53584 zcmb`QdAJ=_neK~7`K2--A|9LC5PnR9A`K+qr{!UF*WxfsGEgUpB|hY%2<5eJkZ z0>U|f2)Q5vwvcl+Y9pPijX*n~v;znNQ9zWz+o0a{uG+uaZ`ImWKl)^}U)ue&eB#Fw zi&J97`}W9}9Pn&ZUH^b@U_ii(u65*H8SHD%LZeHV|o!l0k66-zE z$)7oP%VEX!d>`6=WM}P3zJt9^eeoKDScX!z-EtS{&pZ}8Qi;kI6 zX@!*VQaSPP7pCXuJ-PO9JAq22I{Uy4^Y^dzt^uw4>}}J^l05a$)@9#>*rN+pzH~qi zJc{dtB2D?k@EZ`QL~D!<&Os|mwf!oqsojCkAYd7?V6R1SfZfOoY zQaSPTto396w-cyDH}{8B-<RFXAZ7U~GiT=?a_sCyA|I`5l9;uwr3?4i`oIoY|*4ICjU-!jB2IRmal@qKnX+4}k zCHmv%ot$sC&#VD`jz=mdnpbKkP>Fu^Tc_ryt##Fa96Dxjl+h~6$ba^;uMQ6$?RXUT zvg>9TQW6R+P#KjzsMQs%5Xa6CrlPQO#?PN;zcf ztVX5EMz?+ZtnQXyJZ$3I8(lcQ?S>oW3ol!`_|lsfR_r@Juxb94D>r)s0+k|RE5*p@ ztp|L(yYZYq#2k2(!|kn>Zkf;h$>BwRG!m$k16w(=Y?VdB-J_qI+I5d|ppyOXSMHe4 zT5^6-k46HOB4HOfZaH$r?q>gXK+J*1fAm;;Z;mA&bYj>zY4_O)J)CIXdm zU@OPS*wlG@=D&UNQ!xh~k1PA?=TFL4Kl!SdqnSXZ9N0xYF1zE2{Q1uw8FS$AxU$#y z)j9cBZoQ;ek0t_@a$pxZe(-^fJBKgbIp)CQab@3n=z@I3<4^15Xd+N42X>KTY=!+h ze?4v0m;;Z;mA%E$7v|^QuzN2@6M;%Ouw#yFi*J0g^Qq^)9_Jt)k1KoEB^TxEZ&_ST zWQ_zW<-k^sk?X&+a4f)7cmDOk1PA2|G6Nax$QmiswitDP$>s? zFULD~>zsAjP{%zUSN6pR&d*PO?tOQ5XRgsXZkK&y4m=)L_Qp@0nUBm~ zQsihPP$>s?QK|>lz9ZlMO((@1cs#D`v5y^>zi`2ey?QhesFVX+IYx%wJa+%^zdSfM z=D_1|WiMI&(EQ+=UynJO2~^5~UDRWn$s0`Uc;lyI4m=)L_6ke(&Zn-jv{#QN0+n)L z#~eeut^DxBZnqy3bKvo~vcG-JF8Q=S-_z@lCIXdmU>EiH%|q*T*V7;=KYH)(jwie;=D_1|Wv}t;&GKs(Ozq8&CIXdmU@OPSl$Uou zp*ySlW@wl?rykg`0?x&_MZYNMF2X-XJ-g&@wo%L?rx_i{r+s5zs$07N3!zb_1 zS@gY%{lDKnC;!_@o5Z#nX(Ui761H+=WB0vqSZB9IuT8i|IZ(+S+vxcG?&ZEy^hYCs zN|CT*Jw_kB^Nh~s?QI8ka*|xLu(rF#{cwE`*eCv?>&Bxwe z|OGo|MmyH98Cl&<-jg-9F@(R{`SAli#hOkT-g`@b?f{G`#sRh(L|t94(uYw z!>6A>|fn%N^WZG;M{L z1CPg*ec6Xs$Twf@f?kd$0+n)LE62!`|5)R+?&`06Db7JW9#{6I8%)aQJiUL+(M+IH z4(wQu$$xruUiZ~GD-XNJUO^P@wo2d@wl?T z{>$a_oBw`)v9>o7sFVXcw$Qf3vkN?7h z#d-T!6M;%Ou!|hs9j~4^VOKE5;nn1S;jg zE^7X}^A_ZPoN-1s>;?%EKb0mbyE)}Ki6Dx+cdTjY^I_~kfvekyW9{c59jwS+?B4NjR3_Tor@cGbQ z?(w*?)w5Gh{#=oxkwB$L*kz6ha^Uf}vX@?dNWUJ+F_1u|9N0yFgqnA0D?A=o_Sd#O zD7JJvfl4{B3qm73jH}p#cs#D`uO2w7I<5v1sFVY{k|T~?JRX;P{rS-=RYItQQc;gS z5oT1EIf%;R%2pd{1{bAjB2dvEB{3FOh6$C-JswxK#)4Lin4^(ErAXK%F>v)kr5vm= zMLk{(z4vUdRP4}eRkJ&orCsC*?bK22l^vB6vbhJ{PM}gGY!Ua3J{RWSW4-kXkH?kG zou+mIm2zN5VoEPZ9J_ctF8R03Eg6d5sT8&$P#XKD^kj;T|VKsirGOS}G^1s($^dIYQ~mnmZ9% zA?8pkREdc#Zi=<-<_}B{`Nm^O!V^0eF5N2r{?=n&nqDQ`I@HqHH|$$5lj1*IoBGVRkytV-Ce~m9JgZdbr04tJCym!c{gF zA~DkKaYKx7=12IQ=Y_`^G18`l=7eY`WYbnvf-__hI^)pug0gu+FwKFdPWahtH3w&X zA~-vfttYF_Kjy*MAI$_RXs#xz1bZ)1`F;sc)}{5pQzv})qng7BRHAu8FwKESDkpUP z$$m*ShZCqobJdsTpxve799}m4loELA1TEc8pb{OF4dV)rR8CxU<(u;pclhFfKL6OM zFAeYe?O(;+hzB zus_pIpc2jBH>3m}shseApXw-a0+nd~z9G$lM=B?L*SVU*2~?u_dy_N=9;uvQqK zfl4$_v8MzcshnVSO^KbK*eGX(`|kHQiGML5nk)U3z$29tiuCfMD-GyDCs2uI$0E&v zM=B>)`po2f^ym*3&mmXNOPoL@nqzyK1CLZrXjK|~G;jiyXpSXm4qxGvgX0IQYf9ju zR1ox2JAq2HRy*#oRA&?(shpsn(i~2p63y8_O5l;o35`njud1bT0+ncHbDD$Wwp2RS zYGlX`%4IkMa6-rV!DE+Lii=7%NA0v!cr>+usoRA%&mTlEcpbA$RaaSbG;U15x-=VYY=2ef3vv%`qpUlHGd5qQD z#VOkx2Q4mQ94KWGhEOOj@vDLOGre_gUQIM7Y+vUO9?gwI-sf@;#YAcdz=XUA9EDrD)jk4 z!d0@Bqa2Bm(AW(lE_yT%T&3Stk79m=(Ox0&IN|w%-{!gJ@VLI4P$k^sM3|3ZCQ&NS z;e@O7JL^iC1CJB3`8~`2dhm9!=Ih+Fb=UX5rBaJ(2SL9pcCp`HC-6AY%a@7Hve#$6 zJ?8lRY5P@j^x}>xuJ+qQq|su(y@_yDb%*|dx9k~5`;$vQ)pd^(Vcv`?hwgG@SrbuJ z_4l$O5$CybNTv2EV)f&Oe2e?_2ss84u9B@tWz9qEY(#D49w)RjsT@Urgtiiq)d^S0 zR*tdh*J}((j5|^kC@om;(Zj$L;0ojS?wBH6j%aSf_Da?N%dj$sdz=V6Y^uj-Wp^-^$_ZETdwJwca>(O^ z*>Ptg0KJ-fELVj&AM2FnaE}vKr|F8Xe?{v$;VNsx8lio|fU9+uDQo@Rkeg(5BE5s zo$a6-&{j@VRn0Z`<96kEUe24MOw>G#jM!@$)%1sEs{LLYiSBU%I~|FG2&uvti=!mW zNBuYcEBeDd9@ocPm9QMTYeihm^H{%P_3<3;al&$_U*f-_R8F`mtXDB#u_ij<9w%%} z*K#=Fs<3Lu9F@DsakRU~iO|DSLRm(`{Ls1;{}uIcqN?g2eX2w#yUH0?(a;Kt7gtUj zm9=`f$BEwB-aFzHS&C9QQB^h7!^`f3AK|L?aH6Ves<|Ioe9rrksG7q)PWX9gGvO*7 zXM?hL7Ot`%9G-^Wl7svUG#|hb$9FreeZeC~lv^#Ydsf^_+{q97T-M-)1ojt$*{#bK7b%Iui zZ8f@5_)Da(%{*7n6jjR3n|r*3S$5<`SB<~__MqQzs!n9tj04`^Sz&C$u6vx2&2DrtN}32% zii91BvCD6HJzsLuVKE0Dk1Lyf_;v!7a$pz4!Wp;b_pJWOm_t`4x?|!h<>2=!;hs8C z%@Mh9-XN7`C^?9$Nc>*pfN+m!C$OV-=(#m-%YX6tlR8qdzYC!wry}utm2gj;P>%BG zJoNCiS0IkH?i=U45DeRLX&^9L2FC z7(?=~|1DcPkh+U3+iPAW*r$ZnKBa7SCes`qmwTS=Imj-R6Wk?Db2x!YG;bhE2|Q9c z!9DMkU}u|BQFC^qQvy$&pbgszRHE5iP6<3xInmr7>=ldP&X4ToQG%yVaEB%>l@q8$ zGp17lk5o=DLfZ*cqJ5rM$1WbJoM7~%Ii#YWz1^By7Z3H&v#zpfku--Bs6_DGK}z89 zxUxB4X(v#L;E9Wrz~gacb9XT%e17ouED_B!3XfDyRNk=_&)Gw^xL!GdN;I=MEfpTA zc!Qbj=03+$Cv*o(Z)Hn!IDtyEj%pk~sv{APR8H^~xHN~iuCFV!TT0+j4kvh0p`Ab_ znzyH=1m%^Aw;ai)ekp;cPVm;Lb^;YSbS^QN;4H%l-k#M?pi&OepW3pi(~UNche~>G8O-S-aW^ zRLX%ZVr2BBkDS=Ky4YbUJswv!Yj8V(N;$A&sjffam3f_?zkYH2TM|4TS2o9zb^?`h zV8>ETx%-1BcP`#H?!%QHk1N|}?MNemN;$A&j!rCF_`5ZE7;&;08L~O2|RVe#}$98R@B1@RH8Wsr#b9gw0zP@1n2N6fk!I4t{vxmelVePH4(P9 zmo1$V-nve3ENLfDDPMCBdVknabQw$K1jonrQlV0*INGHIV^k`;(ko{{N-%Tk1ZQgP z1S-+Y=9IuAl@rb5$_Z4WE9+Hd4&tF6I(w1LI8IAN-%4d?;pJ>j37_XqaMs^Wpi(}r zGExGMRCdL(jHPlykgw`(Jky1V4;E~Gq;VOSq-AvdnUdx)uYN;Gf zFk;fSasriTjw>mFM=B>cKDHC6L|3j@D&xvqx882$-(Xb;+ixxVKsj{uDW8sRBv6Ua z(XRaas0!gTRU=04eGt(+Yw<|sgxW2AJHE$~jY_s(O;kq-o;tzqaM~YEpc3s@Uez3U zq;i5*PjfhdN;KD^DS<~SCz|`i2~?svGe~pbk;)034Gtb9PM{La8HaLYLqEQMk9^`C zXX~CcWcY_xF8`09Ea_DY&>G8O-m9O08Y$Q-A61H+= zW4*TOy2sZy2%|mbz~gacbI#aKpi&O(NT}vr+6s@ym91lY z*&mGrD&@c~O0`|+i$_8p_jp{{oTIiAs1ylX#E3>>H_VSXcJX*z*__F?6R4B}I})0M z$`R)v9*;}D@(j6=Pzj|{4s7KJyR=1Hb=>1|Wpl38PM}gG?1Bg@T$eQwkH?j*vA{W8 zToVTpsFVY{$nl-f7g|r;<8ftcOmn`Q4K)#{6bZY?(R4IGr5u`@)MKPPeuUkcGW!v$ z{a2~d?@siO2JUe}w$>QF=Fv=`QY7qHkMj889*--Vb-tZIrAXK!`o|CVcwE_)qk+b5 zJmS;|RQeq|=Fl7z5uez?<8jHC9zQ&mtH=$}KN`5l3E8aqv8~D@PMtud-?1Z69u3^% zab>gSw-cxo2|Kn`dHisX$Ca&dT;7RmBv2_5c2RSVAMWwEvRU)n2~>)NUDiAvKiuPS zWowN|j~{gcm43%AO2zTRJswv!YkoU{N|CTd^p79z@wl>C^V8v){_(>-9#=MNzDm_hpi(64g5db!9*--#dNgPvP$?32k%Oawdpxde*7IMx1O$csrqzC{~^DIhd9T0u?#RwWPe- zCa#WNvKdzpgX`g?a-uTYD>^Clz_n?ofY7Q?ID&_FeUM2jf z#_@I8OXY;00aSB%sZc2gEfU9WrFA*7NX3zC*-PbwN;tSbyi}-^gBFQ%P;YOI?_$-N zm#+Ku+=9;A>@HB{nTagZ+b{KIM-irSqH?dOnXocBTa*9lbm z9lMf4*R`d`~D#xeK6O z)yjKo2NI|h30tM=zX{qs!LHoRVCTM_K&437ktpBm>>lMnMLzBV^xp(sCu|Qn)&rvd zUS|=eiuI66IoRb^shSB?ii8~r-lnU4hSKA4WwXEEPM}gG>`0XFp?8nRmCap;b^?_m zVHX5%f_9I`mCb#Tb^?_mVTT5>mhRwqnJh9_bxLJZg7rsbte4X%1RZDvkiqZ`^}Uuxh6{sG;Jb zB44>umm`tv8V$N$_7Y+%NB=k|0*@22DPcQ-ic-;o{o|l}Jg#i&q#VrzDn-JMM0p%^ zkH;k+ZPh;x)(O>v(T*K!UVagQdPwDQWvdO#?;A7{s1yl1=AZ{V?(w*?H5M4V{ckAL z2~_$WyQl|WL~xJCmF=TFE03IY0+oKpF55~gb*u*-k1Ly1qMbmc9M~fI$3gdaT-mHE z?F1@C!j43F9CVMzC0}K<$Kzm~P}!xTv=IH{pnE*7Y_(x}9IO+l^gFid(f=ZXdpxde zjS`L@%>*h%!j3r@yIuEqT-mHKBKm8)zLmiD$7J(0Fxj+QO5mvzUi0Q0PV*JDGzT6p ziEJMw)f`Ts62aHt(j0g^u5AB$T{Q=uI-xqT!Zj19MDwk^v{ZPca)K`arUafkq5fb^ ztd`0NRHFHkVVVPvR8H`H#gxEPCwxt;mdXiKqWMl_ngfqiPVn{0l)zIb{Af@ul@q8$ z^A*lC2Og=M;M<@nfu~ORaj;q{Cs2v@ub);4pWA$qPek*q#Uqsyd}}YQhZCqo`+8L^ z6&|Ua;9GlX4ku8FZeHQ=Naciog|AvFCs2u2OLP3F60|!itp>9Bu5DTmJaxj)uc|qm zKqcD0+*>8Ce*6CUPxALKmWr<`$5Qzh3(LK5_tXi#kvyOty;vep$!=~dJauBszP((n zhZCqo(+X*+@JQu^e@VHT!wFQPn_G9+nFr=CJ^1c%sTMwQV7~uqJ4ajlWw-1yx%g|@ zO6%gO6W^Hszw+14+4T(wRHC<-GbiRwYmP@MCl0#j*!;xbZ8so?6R1SLdxuZtS5IAG z0D(s;C%(Vl$@!$WtosH8D$&Qic0&I5DUZZAG*$b<$F9%8b#K@w|KvfJ4IuC+t`oC1 z*(2Y6t&84(KqdMuckSI!Dm+p-vElAB^7U8$`G6cwpb~x18T&T0E*`0zm^|f!`E@71 zeL(9vfl4$ZG#w>)q;ldd`|XooGG+4tIh;TxnvtL8@E+XjrGxW>XTPPg5~YN%QBG*y zT=3IuKk26RagHv{2S8uc3E*`v%<-)jKm7Tc$JFL zE}NcJ=>FeS%fs1{Y>sNOIS)z+JavMznw0R8FwaFdmkN(mPOuWCIh;Txnt78Fc%*WI z6}6o}C7O0i2|Q9c!P!|mfl739>w2GiD>RQ1Jc{cCvpFr56R1Qp(^A4~&Q+KQ&QVeV zk5o=@Mb=KB63z8hN^tfn6=#{UE9X9y8O7|B%I71qIn9BmPSA$!1S-+2F)4vZDkqxz z!{<3WA)@K0GzT83oM8W{L zni6>G1lQE<1S-*7Q>O$Tskka$_EI^)EJ$;BJy0nJ*9j?sM=B>OGpal<(KnWlp0j_x z=Q-Dm`!}6s`*Q&OGh})0{J^I9SFYSF5?d|ZGN1dC!=vp_CsYYMqMi8nD|gIiEjhn- z)+dz{sMsH$8)E; zRGa?jhbn>`RXTMHJ~0&plUA_<(0~bHGXwY{*_xV8IZ#X zRHA8-v>rZ6yf?SqaHD+TWlL*keTs!gwiEtjO|^BMKqZ>5xum7SBb5_;!6zl~)CrZ4 zr^2eGasrj;HLut>zx%1F18RQpf%EgzpSxhXRBCDct(|Otj;xx4=hLKGd8Lc;gO7Ro z-gbgmb>g7^xgejp?LEai&nlzc2~?sfZQ53h2C23<`ojF&8+NbEm6Y&V{%D*r_Z`&Kz}%aN;EB<=Acca+W4t6^O4z0D!rK!-p@{q zeeAgWg$rJs-cF!WKF$C1FLLG43ddM_+njClonDw7OU0;6bKnu}#2UZeEWdWa)B&T! z2~?t+N4uAO$?}Kh2jBd9ELC$o@F=bmD=gVNpSsG@0d3_3DsPdr=H6CLeEXVR@@ap* zXFv`oP9Oc>Tr8h4uziTL)uOiCk`-&++E4oUy*0J(3|Z9D$yD}<-Sj)2k}Vd z1fw#|;RGtt&25E8DkqpXX$~h)iKd@Yf;~&An6KeM4*z* z_w`Z&Pn}?mX(v#L=DaH<@JQtZXM-uh{;mkl+hw!2oDz8I1XmXA1S-+&k*5S6shnu8 zhZCqoGt<%>c%*WIc55e4iDm|;1Us8jaegJ6J1HrFr%rHg*G`~{wBIXAR#Dxll8P%N z*^GrW2c9~?bz3`uN;G3ECA{ohaDLrRpc2ifObL!&QgMDQn=_7-z*8rm&CXT#lll3I47zSu9A&P zk+36?z3)%YP2`J?h&k{$A)7OUb^?`hU>C$Xw|%60-6vLyIq-N~*{qfA1S;jg7BMn8 zv{U!#(8BKVxUyNn+X+;Pgk6+sr$bNd-uJn?Cfwt3WpnImCr~L8b|l7*{oW?sBd_Un z-Q#g(vsShfs1ymiAhuZbw284x&x|?ncwE`6G3^8@<-jh9oE&&Ou54DC$e z-`k{fO0TW(cwE^W?b-=c%7Gn;EcAJYKF8y6WwTbc6R4B}TSOeY9mXymk1Lxsrky~g z9N4i`L#y2OkUWK|^6GAAg|lxQUT33u9qpKN4^o8N+?7*~kwyZQB4HP$`us*q^Iw1c<1q&w<#3z( zc}&}v*jy`#$zk?VtHKI+|z3(P$?32L0qxp$2;df@`nlccwE`sX>2D@ zDH67bk+B`G8|tjP;%;5{cwE`s!E7f`DH3*3stxYEGT&mWQ)3Q19#=L`Dzp=*lmj~w zW4}G=uJOJ8J~!sT<8ftk&$FFCr5xA=@ug2cH*v`ikBB+&cwE`sS8pd!DF?QQk+GRK z?ACqxnJF;`9*--VCnMSkRLX%JiP2x5d1`mjvzNzlg~#K{=J|4akR!VPvB3**p5yVjvUz@@oj|1=*aflfQ73h-cT*o&9I89KZF;4vT1ZLaIa=p!I=l^0?@)A)`U66??+7;&s1yl1mTKr{#ryhV z4m=)LHamLl1S;jgE{Gq7{?@xD-Q#g(`(9r*)I^|CBk1Ly<^mYQ3B4HOq=<_apj>qH5X2-LgK&2emk%(_kx-ImHdpxde z_Ile1REmTh3BAFrdwcN)v(n>n$ydzUz%&x_rJrt|Ba(+-IBoLglt+tIYx$-TW{@r{ay|yP$>s?BsxXevN6Rv^~Hnp zBQN-C99Q&*e%ICZqEBYECpp|B+X=6E|EZTcfl9ysed36iJ1y1TYtG7_-g&e#+C|*{ zwgdB(&-h;L*$?-~rgddg!ZZi5TqRq%r!9JXKn^^0f;LQZsD^hP^{=rW^nqx#?swm| zU_cH$QaM4L(i~2p60K4xcS_)q$_ZLMCA=O(R~=dQ4JAwoJj&t3_ivcf(1T8(63vK7 zbKsH63FRBygHE6lT^WhxT>#A-=DBQW+5I(9bFlX&wvJ-aA0OGe8{^Xdw4v&e4ZRlL zZ1jilKe9{ZglyWaoj|2X*pZm>yBTM6Hd?SC9zXDST-mf+JAq0$up=?r%Q4{|k4rxK zBWom7LaC@nNsRT{s_Pz)E8BZ8Ya~!95_YUd_UG^}y`?kGh&k|hT-oYb*2JulK&2em zWsV7Q;PJS!eJzPO1`?>013TtW&AVY-#d_fJxUyNt+6h$3fgOp_zl3(WJ-qYGJswv! zt7|)fN|CT5F{PIyj$J$+mwY-(v=gjql(r-^2h~<_4x;k7vekyHqH)#^Bv2^_wn`OO zh6%k9(LEklw#GtvG|*ZykU*tK*kumAi7n>9<8ftcOjD2k(ODk)R<@5AMM{sg#Fb|d z!ThM^AQrS#vYBbI9_4unaaj|+Z-|r*1>?Eh>WC?K$d1+2@s- z6N|V~$*zp63PCGM#VQK@#y#kSukF>Ed#O;7ub5H4cxbB$)&Haa{ONE6J$y8nqcc~U zG%UOLiqfRv3zu#+UBAEen3uwTov3=Mgy@3!+duvhb3FR3L%UAMMm4d;O)*C|e<1wV z3HQ_q(FHO0J-dbSXW4fy8R|MA8`TS)$77E0UCZ!aC)`sfL>I&zm!1@J?7q%z6HdrR zb?)j}XuE85lbi1h&+j_no;o4AAp9!T3E8OZ_u}tTW2r*cA@|gY9vuiPRo+0{YxP@P zCEQ~X5&Aq3HcC29SPw3?@m3?;Qzw)ojNL%kXzw^- zBQdB(rl`-uya`ucPPnH|6m8Wb^1y2jcASunD$pTMoP$NFN}}qi68(CFwu(fUgQ`av zOE#*|3i0={bxXoMbwYGOggy`Dk8@D{QO1&uD)eUjJ@=Q6NPq(m>vQ?>=aQt%*o%wMj$EC{!V#amLmT zR(`z7DAcsYwgHn$8~%8=Iu#WoP<8ISJ0UIA+UQVgouSjxN}&pag7~9T67Bl#y+8Y` z^JAZxKT1Mo<*x5%t+juiea?O7R@MLSe_J*w-rBsX_Age|j?whB?_2)#$p^+qpZ&&) z>^<-Q=kZrBek9mCZ+U3^x*Pv>rAzEN_42(t?|3$-ww-_9-p^nCOeF63%xv=BZ}$+y zQjUGEKREl1O`i*d)w2GE-B0xqDV7MI!>XOB+HO@|wdd3Wd)NOqwy8|u2`zVoBHg(7 zbWaXXpz>|%R^?mk3H9Mup6hG5Cr~NJ@%7d6XV+#QeExqz?=nu^s_-bTC)V!%o4sHD z?dN-1?g><}s%rhY&EM)FENk#cLKv738VM+SJfhd zDz#~*Ug(a8wKjM{?dRMxqu+?sCGfO~v%c`a?5Cbw?8)H?RH9#X(x!b6?fL3O-5h=d z{n!{i?$3coaXn!(*h4&e=BH;5e)xfzRHN5EJG*(?CBZ)HzF(Z3_?>Ugy1k31O^|z- zKozTcX7M#I*tD-pR8{my)g(&o@C2WvvY!sXS3`hbK^pZp_4qov+sId^MeX^uc}XoU%Dz$z~4@?I;rL!GTV@ z>oCC{EP}H{m+&ff=V5|aQhCB6)hC%oJ3N6(w6(lG!!-!6vX+Na*f2pXsXW06u-kG^ zpb~A@-TL&}s0xo%o>0DgW+)PQ6<253MCv8N z*+43GYT4}hU4mFrQAx7vox0HuUzI1yIXr<%Ik>KLtKwQKRaKon($!M7(c!AyCGfNf zdSRGAm8uG-fiA&0K`Kws3xSw(NB_=`eKGf_Y-_{pA0K#ZCD~)y!vy=Ir@MrY>k0PC zVFDF7ZuqC8Jyltbu{=^S+lSjBg4TM1_1LY-S7JoCcRprSGgnn6*ekm^)K?IwXveWz z?uo`aZ;ZL`D^$MUx>d0zq+(vlZmf?+4m@q5JQF>EN;GS;TNR$93j2y|Ms}D$C4ybM zOW^TwWtV3O>s%_wU|d+aA5_1L3KP?$!0Vt}EQp?_WRbgbOCK%@+g$k0)ev)mDx&fl4{BMO2Ib zed(^r3A=Z1c#n@8^VQEw$^_T;*p8Z57^NJkh0){Vl8+NWnc&(^wGcZ-sjnv9(l%ku1ug(4s83k+O8ZMHcLVdJU(v97fzYOgjE<+ zsU4Zvzi53mw|PZ7g2%^|Z9SdO)MWxy>h(-i>o(?dn^$4XQTezrUwk^Oc9aQD`mr4~ zu`o?J!rVpWE$hMvicNxP3 zDn-H;QSUz9HBs+A-s9tvkKLzCsCKES7NXvLyvN6l`Rd)LOsJ>% z76@BiRqsBr9Z}`u%9fIQ&N6{Yk<89J+*;nRyvN5)`SR{lCam_LO4Vkf-hI5s$CYh8 zop+xyfl86E)wX)~@g5&H=Bsy~GQmz1tF4K8_wgPdmwfC#WkR(}MYRz1?&Cc^Zp_!W zU$qI1hg;`8`&Dd5RQb5F{q9rmS8W27KF8K@ly@IgDPP{Ns?pO&Z=QVrv@6Hj$vC|# zuD7|5uB!jM|FrW({Gf+GrAVAntLis5Z+bw)&zuo+;86~U(7yEDt=h2=s(K>j@B~jF zMeuoO`RJFQxPEfQ&2L-r*}Y1(KOt`~5~vgjTRC=&?tJ3X$t`F7^u&97T-n^W4HKvo z30uT_M?d;&hgZ(n`qq#GkB=*R&3y-1CQvB{wsNeEs_H+c_HW36$Hz_f-uyl15D`=< zMm2K?{_n)e&OrT1Am5FN6#$(QSpz?8L+X&|8qGbY=a$twPTDN&M zXI|m)ab?>~te*%M2~^5~tsMK;ZGFst==3Ycip9N?RM`5Qr(acd@#BX-DMD+|dpyz1 z@e{iieon+IdI%~}B%XMys%k1?bE*oDk1GN?61zYAuKAb#VQIrxB9(6k_n*TADn-H; zv19t;Q{FiL+%+$ldyjIUlFj|@Fo8;uutmIkdiU#2nZJMGS3(XvKCW!;cZUg7%7HE7 zw&@$+^-CL%egF4D4m>`tY`)VOCQvDdDf8X-s&cH51CNiJ@`Z1+l%q^og+Z0tk%Sh>J`CTUDMy(=mBu3z)w+%OgfU0uwA2~^5~t*WX;o4XU{E*>9O zHrK>q0+n)Li&)D~guO@h{N$e;|HbED9Ijneb@$?*oU=7PPizpj*1}&?h_Ia~{Pl)x zJJp2KayJKaS1RV1Y-?Z7(^~Io6Bawqt7bchB?6Uf)_k`rJZ-{yVWwUfCQymKV%x2= z8^8II9)doR%J-E&={MVfr%iAT?pEaqRH;q%Nxw0Is`m{$&r9PR?@UF^Prhq*?Y%GW zX$PJdwCp1fDiQ?qLFzXj2xhoOq;a5~UM>CpagFwvo+O&iamC_xi+5-?4-- z(C6HFhdX-RO@upo@9~6eMmF5h>uw_4(YFay`kZ@p^;LaG?>#=QK8F@jpU8YAQqd;a zjOH+bN|CSwkx!Q1ZJ0o%NZ66!r0+dGu5A7$V3#zJv50A6K@` zl6*og6Q~pkTREyJcf#J|OkPp_m1BF(8kHj zw_ort;Vim3EfJ`c16w)vuYb?JrGCc#0>XQg1C{LQ^}n$E#UqD9jxvEtk+7AcTHk!e z)swgE{Mv^1__(q!{@z=b&%5gJkfThXQY37pSX&$&x?%FG=PraCczj&hKlaGmm-AaG zMFN#_U@J#8QjS;KD0+{NOTN>$#rJW_gesJZc0jC-j-Gz?=>mnpLmatD_i4#c+U@q9AyHPB4JyK1GkR;z}oP zatsit6bU=FBdw^A1CNg@TPy9k+qa~4ln7MHfvp_dM@DSestq~t__!(GEVW~RunL1J zwIdU&>Z=X<3YCv5+j@5&<54D1rC!g({zV(}xvg`?BY1pV*)~h|F|W!5D&@ddUsa1X zcjwGqJU*^$oB8{g?PUU$a$tuX>$V2xtU)|Ju54Si`&j2ykwB#!*dfPMIoM0^__*ZD z`&E%pg;LQDh=r-`iF5WuR6ee3^&$IinLx#OKNF`s*nk1Jan7G zPgk6cE$JGC$H$eeIjt+)Fo8-rur(e#bmi0<4DG<<JZ*xN)~(7DsC$ltVp|pIOdrY{R?ZDSLR< zm#PZmESqY(Iq-CedL}m8;fdC~Vtusc6;JMz!)8f1A<4FO)Xx(e?ZDF}Y&7#3u342Q zP>JSQX1C>dr1FIIbUuqVb9e%kXdBJKiqbginktq0P1o>fyC?LGmRp_S*?pT(4zAA4 zsyu;8w5rYDG&FMHk;)TlQ*nKSSRzo#RPAI&SBMMRYQ3XfEt&|2xw;R#ftS!uoP2yd*X z+CyB~)~5PyqA`NR@+xRf0QK|scrA*1M!NQeH4#6rrkrHTgw-5WiLUpOiFO%XLFHl8 zWHYahm7|X931(>Mt40oA398|$6j$R+g&MWvuS#u#V2%w}g^GNo@rXMPwQK)4{;Jr! zM5q_?&M??lQi-5Py6rGeSQ9C3*l~`(Dpr>W_O5OYKZ2-Yj@TnzLaT@~E^FfWtMUZv zv75tJg-SW-kuIUyd8(q8>x_H+Re3@=I8(RRU}Jp*m2%J{p{o2;?Hl)gJ-pka_n?xU z-<9H>rY50hNO*dPK#Qm>hbpVKkwb5WVe>u~ZwxgFa+HYt*4EVi5>R>ORN@KVM6(>> z9X#b&%S6f%JXGa~{H9)IgsuqHUy;N2l_TnwXM!9hLUgFg;>S}Tl|Y>LiFYpj`RH5p zTh38mquNz@!eXyq`;qpq!?X!h`rPQf%Ga%G`|`oPmpptVSEAY@aWwqaPnS6F6VXFH z2#rS`!A8s51ihf#TRzqPbr{9PLk@^?JJdfPzv?O45yn}xjq>`V|Mp~0%kiWfnP|+b zMmt(Wo@1&?x%>JmdT0lIMX&b~xgDlja$}R{ZfBO{+C5>t-t)US?bf2=^ZpUkdalPH z#ucG_{UhiJR3bD^%*2K1UG`4Vm+V~`dFb7}-#KB!k0!SIYXABXd#?1nJzpZ0`rQ+< z>4jke741+@i-_--oM>;+d5@19^VPjuCVcN=D@A_?%9nSzGGXlqs#I+z_Agpr&FL#tKCW!*-Mn9w2~^5~t?`KOm@wveeB79?-gnD{ z&84tA$9B|2e8+^ji^|6(AG5tos6uuhY&B!Y)YjmfHHgQ@jrr<5u}r9^*|o8iW4CsO z4R!`RKCWyN=Dod4po;UVz8aKwABdDM?8o+*dtM@sA3;B3v`gjtsC@m1^+r#M8)jep zyj~ym-rgoyABkRK4K@kiSAJ}cuPRS4d%7(rR;(n>KH2n0moQJbl2JRmHj%mno-R?3 zd9&r7uy|o+B)aG7OkDM%Y*onqNTlJaJmL5Da#g6v#~Q3p`ub~b{vtv4p*J0w-Sv{s zhBw3bYlvo5`nH(AXp;T!_x;!S55ICS{ANx4*Hn53>!e+m&u_YO>)gi`QOeOI$nFW* ze6Ff4Z{)z^Rm#n;lynI^o{-JwBC655tqogtT|QAP|I0Sm`kX%O5_l9BLN=dA;^!^L z`6&k;ukwA^CFoI4$mVkq+ee!%{(J7+8rtDU4O=-F*)D-caUo>$c_dD;9KV}#;PEQo zhh4(=kEi)u#KQFVE&ho%w-k$!QVwi=?q_0?z~c$od>(VW#&VpKa^UeQ<)9b31RhVw z=5rCvHAriH?d=@(I#(<|OZ?1lj`_aB-`)3$m)5Yp&`sOf8@OVNtzhF2_pi&NO5o?QEKmPjp$F6%($brYlm2JOA7=9UXm_Vf* z*nwC-`=vL{Hy{4)viJD7viWtvVFHyRVT)LuUi9m4oB#bE-@oBKKCWzjwQ!g~rAXK! zu9?2+!87N-^_P<{+wu6gvia4*VFHzMV2jv2efufz*tq-l>q8DaKCW#2oh`qHSSC;@ zhvpl^s&cH51CNiJ^5x$hEE85?P^ETcVr|{}YC>P3@^NKbAJ)G$StL-U@yJBAXk$KM z%u)HcvTc^+-^?r%sFVX+<6$R#Td~YtJU*^$ey?+wK&2emBGyK>1}CgRJU*^$TbtpR zT!#r%%7Jaf>e|Tmk`?w6JU*^$+hh2>*8u{Ra$v`*Y=>Lc4(B~Su58UW?R-^r#p-*O zY>rOf@q?Q?1gaFN=l5P?thJZ9T{P5Aj{Gh_K83dl<&a9Bv%7|NGzc5>@Vl;3+1P}A z@K`zOxSp_H@A(y4A4@hW+2yKO+fw;mf;M&Afu~Kdj|~&3MAIW(!mkg%9?9J$@F=b) z*fE9)RHEsTF2Nj?%FldqcL_Xgg0(qJpb|}wh}f-P*wF7rg?HR--G?`W^c>&61%n-O zjP%6of9?PDMn!lV$P==83uc%=rAXK!s?n2H(KA+=_xQLmU;TDXnegw*V22!wDaS@^ zM~vm;l8?7*sv^NVI8+OSQwPHab1`M9z* z6M0*OdeK1EB(m^X6}%d1kpFvq$%tgk{ZN~H=_JM^(f Q&=Y=dFIR<%d~pr_A59&cvH$=8 diff --git a/src/arm_assembly/meshes/wirstBase_link.STL b/src/arm_assembly/meshes/wirstBase_link.STL deleted file mode 100644 index 0e2de13505b41fccf08796b9ec470ce260105d92..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12484 zcmb`NPsnan6~+&wK?D&96&4ZEeF++dbm{&6I4Pt_1`Vtx5)DF>Afl9lzVZ$n1Uaxt zh&9kxoJ2^F^?u)dCwI`G;8GwGcDn=@p~MU)LIYjT+WT4iS!eHaY>*(V@2vG(&tCig zIq#jO|L=cqdb+d2G~K*3O@Gb% zkY(bzJ4zHYec^-O9uh5T^XcDgKm7A=RgLRMOGNP??~K?!@Yk_MBdjKm0{!RLetYzh zuRbzp6+N}>K|t??JHI<1Q0=>Z@UXZ2cVGO>(Wh?x$n9l<9%v}>+5i6ZXnN>}0}Uk@ zwO&UawKkg8+Wpc97Ei4_#^3tw9CKkb=85nq(AL^LMzbgAsTx5*V?5?_0#TLTFOIo; zs6oO;_Iy0%rXB>NSjTwG(JFWlrG$;m`Qiu$!Kl*0d-s?Nt%~)bgxTA%hOQ_^)fW2da*b2l zub#2}YWL9(JmCA)WB+>p7B**oeSVJTL&7~hA?stV5d>EeHDd10h_W*v%4Ur3AF#QC zN3AOAmGD*cP8wz942ZTqX02)jXFh1oc#p<8mzEJMdg;M?YoJfXHHlP zx3SI_2}acxw(}zq7UiBA<$0+W`_&?W5kwR<7U$IwXJRJgdS%6#hyt|&w)!PT`+Fp8~;y(HCv_QHcGCCqMn$r|BNwT`wYCIagYdt%iHf_vAn zjvyEXnmc$;(1R!?xCgHji~`Md17g~h8`C}9ul&3#J7-#tv0wEBW{DECc{;BXh_Y54 z+bS4qgh%t5?azlAN<3N7TOZ zDADs<%{vpduPzof!oya9Fx#I;Uumn9h$zew?n+&&!lQXja}fFIP?vqLkp?)oUohDA4Tnp2)MW zyg`7l`q~@hY?j3PpwFecqF~3W&1247C2zdrpmIN{`&Q92Cv**FjXA-2Y{cMRQuDfp z8YHZ*26vx1!6-b3c7MN84{RlDY}y-S>Rsjn!6?}1!+8Hl1U+-YX3XFguDM_{3O3h@ zkH>-E8L+q01DizI^QBdZV5{Z?>+3bJFV*{1?1@FAogeL6hI(Lg9+&4bcW13CxipHI zVi!$>R?G1Kv0Mi|h*E;%-&d{#qiU<#+)b_GtVYy~@N>7ZCzWZAlPZ z&Ao=s5*`1v?@1-J;wxC(y$2EK!0{)WB-) zTLpsaJQMOppTnaydBTNr7W~>o}Mj;x1N98teFWdY*JJibe@+Rc(BJ4N56}=dQdhDKnp61&N?6~!< z5+21~A8C{sF1Jb7n5LI}w)cd3%B?1~s?xSIL>)6C>ZqgXJ>uhG#NFOk>e0%z4?Duw zHriXqfIW?IO06my+IA%@+IOG6awRmXKKGu^tx}H?Rd1^rrB&+Tyh4;_TGJ@=wdC~? zOd4e-=3Fhxo_F&q`bs>FsN*!&2tuQ*KI~UP+<)otjRz0E`tdbW9#FT>w_N63)|L;zbC8{jDiMj5Eq-jKYHcrtDpa#&nv#s zAusJhw70uVU_Ik*s6=U1BktSWcKcn2f82JLYbZe*8rc1K-^~O)nin>oqmHwut%ifu z;(G}_8dWQAZ+D5XK8Y_AO7l51zPWqFG;Y6g<*Mc?ttvF@;FpO^AaDI;6l0L|NL<_1 zzB*_w)`6&^-M#^20zF!P8IAYl(!xgE+TwTfy-@mY|KwN z=JaS(siVCQX2QnV-xQT7dX0E^gZ0O`s|0P0OFa_Tum;grz6O<`&GF#B zfXD=Tlb#bX)S4kYH4)W8p^Ty<7M8L}Q$I8eG+TVj>s?4gGf+nV^T` zK|MZ49XIs+h+H5TRqODRs3)u?JfniBdO@U94Rr)TyN*YEd(DLPD9_qN^Eq0TPG|IJ z5VT7j3pW7E8+V38^EouqEh7<(Vja9$W&$m#chN-iIV93;$y-8#Q5+BcN|p)qXuXRj zn$Mwe(0iiyC<#VE1LM!%CNe<}$C)&DqG|f4-E&{H`|dP7zrmWr*GzmPp^dL~R*!$V zE8k9(P|t`c-}>ILJ1G92rjKoupp7W2$90N^66zTdMFTaUWz+O)`#RTh(JoQ#`^+>c zQNP3ax0g(`FP=`E6pbhCdz|KKQAYb$wo->_1d%;G5q))9`s(GK60{Lzy&zwTEIJ7F zjEJIPHJtjG-+ybT1Z_lNop3JrED1tABO+S(!WOC9@|SI}^x=5^1AC>pi$ zQ=3<;!wJ%*j`ABq%q#Sj6SaR9iK04NQi67g^0`p!P(r`&W}^KT5;M^>p0IDc znyW<_?c*Nv3bWmb?CFW&P|t`c8dw`Xf|qY`owIj6 WFQRNTV~>g5=VUTMJ=9a8XuJ)<^e)~2 diff --git a/src/arm_assembly/meshes/wrist_link.STL b/src/arm_assembly/meshes/wrist_link.STL deleted file mode 100644 index 0e6b6ab511e886d43f894b64b5e3ff6133b1c466..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 50884 zcmb__4Xm|kb=6HNkQi#Aqomei0cSp_MW% z^(7<62lg39lnlMrTSaf7W{fk==2FA4^s`X3(W*UG$qK_BqR`tt=A-)INQX71jJx(k z^S{N~?S5c%3#Itg`%Ol9lOesc!wjRM=cPGqm3l6XhdEZZzp7S^49(4oM)uMuk1T(# z_G4#OGGH?YuVxfV5tzZn`0}-*qo2g<#^pm#{KVOfge+U0RTeV=6$LRQ3 zt-X>_s2{ofnX}*h(pzeMO&RG?>|%WWowuAl1CH z8HrNQR~YGe&h-b5U;nB*-SdvL-KrUb`|Z7l`vGsG)br9=)o=@%A-&^GjbbEfKIb=1 zaXR0J)A<_Jwd?QIlFGYztELQj7mP`sPc)KYRJ=Fr3=>A8VDrSW9)GSd_^w{N8Kd?` zj_#r#%>dK8C`W`R&WeUTK<{Fw-dX#w#*}dvgL_5*5&OIvzphZ#nZq5hS| zmv7>9#_PtZ)D^#XxLxdzHC7XbcQubqv19L=G14>BbA+oIg^WFM#)wmfNVbTtU7RH| zMtYJ#mf0NLvF9^Jqv9l*X{0CPZjWyEBTi>)RiCD<%C;vXZU(bfB_mPpHCwu>!B*^& zA)7a~86!Pvm9we(uw>w!_9R0iQta(kC5o~AS}@v^49)DiMl%vMUy0Af$;{jSyZG!( z#$GSm{#oy{RTGBM{Ar|r)_cXkxx=&YU3CKxk|@83EHvL+Fxs=h*pu<>`~KoL|Gm@y z^za|Q{(nC8-w=1P;~evS?{;L|b@P+|`iD-x@|CX?!yam+?cMb-!zgOlCgX!Q&)#EHi@FFZ{THH=c9`ZU;P09mM^e}hepM{d6GY4>0M`M3X#(l9FH()Q_dm|+w(Y?CqW zCF#kyvUziwWz-6zP@?En_(0+Y_lH^b3QITANJs9qiADp z`ZIuShEde8O^u)8y1MkbvM1xx#u}?n5DqhpqK0iU9)A<7{nD%5o{US|x3j|xqlU5K zeeOox0G@rDG%nJUaYL`p^KFJ&cozLA#$DGmR;6K7#-*(>tUTXl7)1@+?D+?;Y0fXx zlW}R|#dTF0+YFD1bhO>)|?NiN+(Bthk zK2KD8YnP$@&;RQ~`;WcjEj!v6k>26P&-&6cXZ+2l-oM9dx72VfGK`{)mNBDN7{iWp z<5r^H^r_G9KmT37=+n9P#A&OvGZZQrf8pOgy8rQ?I9bt1hEdt4Wk1BIJxUs7yR}P( zJ<*S1yz!s?POaO+45Na*GK1a$h(b^I>rSZmd=laXN*ZO!Zo z!#e{}JTKT6+HUPq!=5<&c{fjB!NiE^gWcCIWL*;}pM>c@7^?P1(x zD7#krkqo2MLaz2Y2d6WbD=`^b$157iFp3&p$IG5$mDIjV6f?-{$}_uU*fVD^dpBpW zPZ^`g_KI0*W#HkS;0h)M>=t=95khEZf=p8CX@&WAljC4>7R*T7OE8Ag%q zQC~9bAu1W%vAG5gGmIkJv$7yAa~PVEB|1&$Pqugo#RqQNdoxLCs)|kLJ8=w{|&J_AqWTv?{OYxlz%o z_0xbERV~pxdj^@!D;io?3x-zA6%3=;Dv!vr=k^el46Wl8jbs>=|xwwAojh(8kn#4WEe#@-mg(#w#pu&lA+yhrRT{oifqs3(a~Rh`|k3VmpFeo925qmgk+EB0 z7{y2*d*jnj{?eD;D2*E*{KnIZ>pxo>_GDbzUipK@7Q-lN{G%Ux^2uku?iZ!;nO}YU z>94>4)1_fg#-;5QGiZ?U*%gLS)cD2^{q~Npfk8A`>B+dXy^aqvjAA7Afh`^w94GcZ zJsFqwbk4UJMlllSf+Ig@ya2Puc~4KqrR_B~FgV|945Ju{Yl>@YV0=ARAy;F1GA?be z{G+2+VkL6j{=OB4QH+GlyLVXEWI*HG40|%J^mtFy3_|1Ftx5*^Q7E-`KlTH;ap9h$ zhvmt*w7tjlSgkUQq6X$;Kh6hc@WOL$PsXK<6|?8+A2hZYMo|OnYCo^9u00u- zHdcO}^MeLf`zpgIY9KfEV}2n1r8CN&j7uAR*mLy{8e0sbsDVD5k9m%9y5x#aPsXK< zooLV1KWJ<*jAA6r#re2jVZJY!Bk9Sww6Uh@`E$@9!+WA*C5n--rq0KG7psu#w{~iK zl0lnKM_8r!RE?`0E4^|gV{u`#)6^Vo`p7Art{;HIg*}? zOIsry42;!+VH6{248_n47Q>#5OIs`E3WibC(7F_kvYRCzOO70 zLm73Mo{URd8GHr9C`M8?W8OI*+8Ij2o{URdJCQWD7)DV;yOK1J8{FYa!=8*wTRW;W zINxgwqo|?XRT^Bk%#rkDT-rDpj)ol3`N7j*!7z%EVBb3Ah|Uk5IK{9h<4R9YsT^IN zQEpW-bPn#-TAqXI2k%zyxlYLQj7yt)6<7Z-gF0*7kBXHjYH+V&CiI;1&QJ_{l0ln$ zE?56yhEdeup358=7`$6CN79pVX=CMAjtmT*1ZxbV7>Q>Gb7Wuu%^O)|lsy@jHu_LG za+qNhHFyRx69xvxiFZ+FZFw>-ZOldG$YF+2)WBR+jtmUU_bGEEJsFp_Zsgi`$?%@& zSczgJ-bt7vg9dLg-rMa-25mpF_W5z@y*(L5QNzy+Bg1EuJsCIj@XYzrCp`D`KR)Am zm$yG~kDouVc5dAI`@iS*li&O&-*o=Aul)A0`k`}>jQ{d&f9&$l{NT&3rzaV-KlbjY zoWJ3_e{_f6y@K&;V7zRFVH6|jln~>uz47Un5B&7|O2eLvOZ#hn@8ixNdL}=oei<}g z4aWT|45O$q-b;P}j9>b|lP+)hjn9^bJsFqwBme!^_IRmP4}$RrRv1Q6L+6JWPyLP0 zUOe=HC!MAz%wlQSlW}QdwVYwqfWcMrQZPQV!Z3;&IzPntz6b6( z{}0c2UTN5qacLhNedOLd-~BZF{61)W2N=J)!Z3;&er7m2`d+pQEB%vV*pqRkcRcok zxq%$1RwaYEL6rKzJzxD`ZXie8kMd+(+RTk{KA0OGU7a{5iPC)Nd5|;6+(3?aKFX5} z+RTk%U2&B#H;^L>hEdee`GJ0LB{DaVBgL>MF<|KYV2&&pMp0wDm+1UpjugY5j7wW9U#((pAV(Gqqp0Cq z)X;OTbmYiodNM9;W$<~QAJ>s13x-jQq-+L5=g0NCaeAgFiC1%}R#>&TG>!zf1b zt#)8AH+Tz3PsXLK9TgfnKdvK377U{pNqeOj%njs7G3?2>wD|;p)enZwj}zp`f?*Uj zcpn;`KXiVaBS(s1PsWuV&q1|{xxqVD#!8g>u}4OW!Q9{-D?Q1ejgjVg4hH9gx#7{( z$$6eAM$)M*26KaVtn?&-GVL&W{V;vC@-qX=CN{ex>|i zZt#vZXBfrzb-xmWxxpJ#dNM9;_JOVJ^JA4^6eH<22!_s&OWv{4lW}QtE;uK{d@wh7 z$C@*Y;``W@&N(LogR{pwR(dinZLTS-e(k%=4c@Wl45Roy*A&-7pC6aJW2GnK(jIby zpI_?;|ClD4vTuE8?!Bp{OH%N zXe7fZvYn4h4SR@6#*;qutn(M$|L?Kd=lw{AQDi$GmkfJ|O2)-+e&_kef8w4Mjbs=_ zw)1hRVGmKs_+P(%=lR9|e)5V&GK?bI`MA`uhp1#+-1*&@i{W2?PIE9BMnykXvR17+ zu6`(P=fXrJ=R3!muaf($@T6!7z#pt?3npJsFp_ z*73=5tde0A8OqHShCLaVw({``hEZf_k6B^ZlW}QlU%7%|6dBqpR~U)Xo>))C+YEac zHyJt&Ry2}f6xqlPea|D6+BM^f|*^!yclNfiqLP7}Kf#H!lIO`Vifrs-H783Adx%N~_O270I4c^- zFp6yKu62`IYS=?mGO!1q;KW(cNQO~lKXJ|4dBd3XHS>D!+6*6ZnET%%|^gAX$r zMeW#2o`3Uo-}BE!FcfIo&W9$r@!)^KVKU5 zWL(-l;i$3AXcRQs2IJA2H-GDa>;LdWf4wy9$+)zAQd47_(I{xN4aOI5e)8G7>rcP; z@0Nx=8JBk6WVRWNf=1iW7{5QrIkzX{%I0(Q3Hx!7F`$M>!9YJQ+z)7!C*#sa|M+|^ zjV(r_hOuhKW1No*&xcVNmp0~!&*!DF&1e)f+D6YG;kvr?y0RzZ(#Cq@^Lc4(Ga3br zwxRJL^W)O_VNb@TjlALWd1-7j8U>BEq48ek`K9yRo{UQy`OoL`9S8>)je|=aBFO6+RqoC0?G@gGG`|hRpU3)SvZS28(J}-@JMx&t7HZ&f%52wMU zPXl{0Zt2DI`8LDP=ghRh9&Thue^?sl>B+dES9gYOhFZ91q_)wIhi}tZU8E=DmR@{b zvdz#)mqy#1k87Iq(y%Av($-q2erz)ug?_XRjkjLY+P!2y?8&&awWiNOIKXHWBDD?1 z`>!bnOT(UwOIx{F8rzIUL8EPGJa|oeNom-VacOIhDUEGLqoC0?G#iw`Do!_GDby$NmiYAY(uck%FPK zw)z2$@?>1v=pUcxs~=xx&v`m87>ydnsu_=QK6q#FSd}N^(#AaTiM}+p8I6KQ+Zd}y zxUP8jDGhrvE^VwgKGB!PHltC{Xd4<2GCz2SD-C-xE^XuupXf_to6#s}v<;2-GS7Jz zEe(4zE^XvLpXh5Z*=95f8f`=4P28_|r>_0Vo{UQy`xu|-OJkeSC}^||jptv}vw`=- zij{F`W2fd5z4pW{Mx&t7HZ=atZF*v<^TVEuTYB+Czs>OTIWw(oXx!L*Dl#hcb|6Hh zDaIPU=Y{hQw!axj+pS$P+LJBGNC!3Cs?fNiRnn`cJAY$r*(!ZMs?I*Im`R@&t;*ge zBUi~-k8Bc)J@@K6I9C2H8QI!>>gm|rt*h4;Hp3k}TR@EvfVFdxHjDq(kP7mW7I z7?_*!cd3(BC8JSbcb~R2YQ3sYWs9-0N-|S5AKn=@vbOUXElGyPYDFU%jRLz{xadcF zfJ%nuW^es`W~;qpB?`7OcqOAU zCp0(JDvaSqezXU1lYw#To8=;Fhge`V3O2@Y7?DLk+B0Kdr28&9)ksF8z{X1Ko8_Ew z7ssP+0N8_v-Y z4z7^lcPx{2m5fG>dMo|tdu0j(uju-46VK500R>yRSsL36 zqZr9HHO6Xh6Hms4tt=>wZH7^dWSbgeeYlAy^@ z2N^~&l5J{?_2DL-j0?MWjDrlL7|Av@#%ga9PsSbf>i4zV47L3%T3d`)bbYvqC*#7_ z=#FKGhBcr(5OJkd16eHQD#`tN} z#FKFc``8)>8HG}$W{lO|CZ3E78$ItEz&67uMzYO*jMd&Io{S3{GuZd5ZH7^dWSbge zeYlAyQJkO z^-6ZGk|_hDSkG!g@gB5K?Zd4?+-9IvJfkYlryAK0qtvG}XYG`sxI3cM!n(;g(&1Jm z19QU`T`}iIgyv{jn5YL#ZQ?60m>$ErVnB~O z+|{ir6!knJY}KT42{Q!PCiS9WLAK}MkzsTt$xoSuwJ8?Vmu zZH7^dWSjjMZyD*yxU?~YwXYmz7{y4o$(U5rZBNFftzDw>e4AkuHEdJk+p~^vdonI< z?JFc4U>G%w2=}YuuUb7W>me)FjrzMNW`tgyINJ=hoi*s(+G33N_Vi?2+8W*38MYZl zF_LZee0-WnPsXK<7uQv3Y%`2vB-_*&pNi6xacLu?xY|o&n_(0q*`~($beEotEBn|Q z2N{J@q-Kmysp-kMwDGDvn627o7{y4o$@pN_Z*Nb=rHvV^v*a+tC~DXyV^W8{JsFoa zR%L%OvCS}w8n&r1-V@W4acK`H(U4Kw45Nmz;^!#Cf7_>;8KF13GccBG6RCxD*OJEG zc|P7UQeBL?tJ5B9a^yXc9<9;+z#evI+OCnqo=i2eRjzDAhIWaSe%M1)GF-E0sgVq$ z$kxt)-p^ZQ4^hc*&7#8$qsYdb^cgknxjjTB!!?VR8p$wPIu6ry4@bu^Jghsa4$JRx~`fM7atSZD-nYKJ1w@ zh#cl;-l}96C5;-9RgE62WVpW5VTMuE@JKHi-ergyYVRB!(H?d?;^+OaXU8Ahq+Jg-(}Fn73Q=ww*YNQP1BxhfUT*OhjL z>Mh2F)!55c-mGZY!??*%24BH2ifr$8%lXjmQ!P;zxmA6Ko37pLM>3R;>#eF-Y>83X zr)8@$i?pt)Ra$TBGg!ICxXI8uUTKwMkzo{V<;@Dio;gGLcm=~KvOVg{p4&rIGPGl? zXe7fZvOPCd!R(Y3%v6u;T-C*DA9SYTTmR>(OtT*ttdgc$lkH(#GiYn1gQ2==6NXXL za7C9vBkIGoC*#uA+(=`KVH7o7(PhwJojcWjjkxtFp1G z@3kl6()OM|v?}WLO&CT|W32T;4c1{*-NE)`T-us*^<#@+6g9?LFVs-2Vpj2JPsXLK z43% zg9aJi6CEp2)EH~MP=l*bwI4BEPZ-&d6*Pr1^)w>ws%s4>)fISPhqO|~Z)p@*~9 ztzsT#tVBgWc4N<3k2O8XpskS(2KSRW!zjM5F%&~HSPXkIE^V!tD;P#mL+eTmu0+;j zO;5(9t(6}P?(cJkQG8$dAqH~;I;ZK$xU`kQS1^oXBxN&x@5UKqZeYAh!=8*wTlFgJLcNl!9p ziA}X8J656?NvDJus#RPX_9TNgDm|Q|N&*q@nXi=p#_we&hJZC4N(R*7mAFBnEqL#G5Zm>;TD zTnu|ME^XH}8Cs=U#S4Z})X*uRJXfva$|!p>E^SwI8Cs=U#S4Z})X@2%o#F1GRHS>@%%uo$xGELK1ol;4LzKLIzL#ec)?IVSnJ;X*bNNU z@n(*sC*#uANQ1%E&e3I#%o#@UeT}*ps#RPJdonI$ zX=^6}gY&^U-prAVl_uM7Yw5`hWwOD4Am+w26r)fGA?bb7~V_3;3{DqZ`Hc@-JlpoQG+`x z*L9yCtW{hZ_GDbzx;ZI7RI7NwFp3(wUx}ew#g$R^WL(NhVoAt_7Ihf{zlzGBN;}K?Yq{pRrU~-jQ&R5LL(VQk*z&=r62YXm5lXo z>SZk2M$z_NYuOKb=8W}kPG&6HM$y*ExnFA7GiTtNXk7zhI)lkDifo7)7@4TFbGrhp1!>RS{H2c#_i8`(Ug z)GF2yK2L`9urnND7)7?maD`z{^n+D_J#JSpG`hvmT3BJ&lW}Ql{;yydMTW9qg<(&| zrLC2ZQ*Az0$uNoxW%CNdo{URd8GHr9C^EFitT61!xU{veT){Ak4DFRGj6`Wq^c|(D z>@LU3u^2ZQ+O=0Sl3^6th<%?kVVdXm5S0wrXReHQkWnc0Tz9znoTF9ckw!Dnr@brV zO*N8X6xo<3ekQZhb9;zN21dOr<4rY^VHDX|Z@R32e8@YiTng8q0^w3U*zVD9TLC#y{Skg<(&|rLC3Eoo;qRPKHrrC^uIa_GDbz%Ev1hMv#eZAPP@(Ka+DRnpp%acN^6_q~0a(I{xN4UI{)xAtUQ+E~Y3gKnGA zC}^||jY-wI_GDbzSjS!QWSh|_XtWKDN%g(m{e(QPsT01xFK&dGzX>8Hd-~QHtqTFXA5=nriNBYwQ8HuDD0c>jcrDw zpwTuoCe_&6lW}QlM=gzQMx&t7HZ;D>dit(I-=2(1TX(I}*k&{e8f}*bPMn){`wLIT zmCZYxG!8HZ)DWo|U(CM?K=txuT-xY4&-2pQW;ALTt7c68T0zIkxU?~YyqA>5HltC{ zXd7cS`Kt@<$+)z!5_!KWjcrDwpwTuoCVxGmJsFoaGK%-a(%5D+3L0%gZ?aBKvV)9{1yr7cc}9(Y>2IPAMx$VNYZv{H##yv#PrF;YV6R6 zTTutt<7M^Rg)UAW?xq?Y3vnAY^n94jEsa`z(qL6!uice( zm1{Q{8ikYPDoIA8pwTOT(JIYawM27XwpPzdtJ;IO$eatO+GeQjtg`9W7GtdTHt}R! z*c#m(TeZzFiji!SF;;tTqaXLZ{l_n#_4R-I;^^pW-@`Zvp{lBF@1Ar0f#cV|>ds^MXN>d& zI~lv9qr2aIdim;)ek*42_q-<=Veh_h_iK+|cl~|RNJe@#7|{6mJ-=}AT|e}CXgqQ= z8Da0pK|&Q_x}JiK5}a^!ruMJ<Yf_E?=w z`cVwEy*$BA#yB77%h9uv5w_=C8k&z{Xb#G=!GMNV2^jz4S~9}++LcB!w3f=V!GMNV zJ2W1=Eg4}u2c?k=AGLgVSq!D0m4JA*Wmq1-;ifQI%f%-~0ECL`<}=DPQ> LDI+}_3~2mc!n>=> diff --git a/src/arm_assembly/package.xml b/src/arm_assembly/package.xml deleted file mode 100644 index b357a057..00000000 --- a/src/arm_assembly/package.xml +++ /dev/null @@ -1,21 +0,0 @@ - - arm_assembly - 1.0.0 - -

URDF Description package for arm_assembly

-

This package contains configuration data, 3D models and launch files -for arm_assembly robot

- - TODO - - BSD - catkin - roslaunch - robot_state_publisher - rviz - joint_state_publisher_gui - gazebo - - - - \ No newline at end of file diff --git a/src/arm_assembly/urdf/arm_assembly.csv b/src/arm_assembly/urdf/arm_assembly.csv deleted file mode 100644 index 06858e24..00000000 --- a/src/arm_assembly/urdf/arm_assembly.csv +++ /dev/null @@ -1,8 +0,0 @@ -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,1.03582841131364E-18,0.015606490089144,1.93574980271696E-18,0,0,0,0.93972387307473,0.00251429022255044,8.65861551705636E-21,-7.37485241366082E-20,0.0044229329573873,2.27711298016934E-20,0.0021336882069818,0,0,0,0,0,0,package://arm_assembly/meshes/base_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/base_link.stl,,base-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, -shoulderBase_link,-0.0122586821821901,0.128577249577976,-0.00370544350042927,0,0,0,0.996366805002727,0.00652370094208947,0.0010646616036529,0.000283127005277364,0.0050231810993567,6.82113719161566E-05,0.0086334538259584,0,0,0,0,0,0,package://arm_assembly/meshes/shoulderBase_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/shoulderBase_link.stl,,Shoulder-1,Origin_turntable,Axis_turntable,turntable,continuous,0,0,0.035865,1.5708,0,-0.25129,base_link,0,1,0,,,,,,,,,,,, -upperArm_link,0.0143973999054565,-3.20061625687929E-05,0.279348384794928,0,0,0,0.985210343915811,0.0237982224738339,-8.87977733299251E-07,-0.00388532856230119,0.0293594722597602,-7.12944369971275E-06,0.00625034839320104,0,0,0,0,0,0,package://arm_assembly/meshes/upperArm_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/upperArm_link.stl,,UpperArm-1,Origin_shoulder,Axis_shoulder,shoulder,continuous,0,0.18098,0.043071,-1.1021,0,0,shoulderBase_link,1,0,0,,,,,,,,,,,, -forarm_link,1.84574577843932E-15,0.0550154986611603,0.120152803034247,0,0,0,0.517796101730459,0.00404850874710771,2.11419423634673E-18,-1.54871504075976E-17,0.00375548329392274,-0.000377385363706529,0.000788327838226562,0,0,0,0,0,0,package://arm_assembly/meshes/forarm_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/forarm_link.stl,,Forarm-1,Origin_elbow,Axis_elbow,elbow,continuous,0,0,0.46634,2.4936,0,0,upperArm_link,1,0,0,,,,,,,,,,,, -wirstBase_link,-1.94289029309402E-16,-1.66533453693773E-15,0.0987034845564234,0,0,0,0.301763082175337,0.00210344289702837,-2.71050543121376E-19,-2.24971950790742E-18,0.00305016250706558,1.85669622038143E-18,0.00107609106501786,0,0,0,0,0,0,package://arm_assembly/meshes/wirstBase_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/wirstBase_link.stl,,WristStructure-1,Origin_forearm_roll,Axis_forearm_roll,forearm_roll,continuous,0,0.04445,0.2285,0,0,0,forarm_link,0,0,1,,,,,,,,,,,, -wrist_link,4.30211422042248E-16,-2.77555756156289E-17,0,0,0,0,0.447707117943176,0.000367702266904795,1.79994501291539E-19,-7.45388993583784E-19,0.000843427086265753,-1.35525271560688E-20,0.00084474612356066,0,0,0,0,0,0,package://arm_assembly/meshes/wrist_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/wrist_link.stl,,Wrist-1,Origin_wrist_pitch,Axis_wrist_pitch,wrist_pitch,continuous,0,0,0.23716,-1.333,0,0,wirstBase_link,1,0,0,,,,,,,,,,,, -manipulator_link,-0.000730323740460503,-0.000899365669252,0.0490560099953423,0,0,0,0.397420225554811,0.00159684305263878,-3.07243227891656E-06,2.53235579936151E-05,0.0016343224414688,5.00292290874635E-05,0.000256322563994287,0,0,0,0,0,0,package://arm_assembly/meshes/manipulator_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://arm_assembly/meshes/manipulator_link.stl,,Manipulator-1,Origin_wrist_roll,Axis_wrist_roll,wrist_roll,continuous,0,0,0,0,0,0.096862,wrist_link,0,0,1,,,,,,,,,,,, diff --git a/src/arm_assembly/urdf/arm_assembly.urdf b/src/arm_assembly/urdf/arm_assembly.urdf deleted file mode 100644 index 7cce560c..00000000 --- a/src/arm_assembly/urdf/arm_assembly.urdf +++ /dev/null @@ -1,282 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - - / - - - \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/ArmControlSystem.cpp b/src/wr_control_drive_arm/src/ArmControlSystem.cpp index b70b54ec..a7681e89 100644 --- a/src/wr_control_drive_arm/src/ArmControlSystem.cpp +++ b/src/wr_control_drive_arm/src/ArmControlSystem.cpp @@ -88,9 +88,13 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server std::cout << "start exec: " << goal->trajectory.points.size() << std::endl; // For each point in the trajectory execution sequence... + for(const auto& name : goal->trajectory.joint_names){ + std::cout << name << "\t"; + } + std::cout << std::endl; for(const auto &currTargetPosition : goal->trajectory.points){ for(double pos : currTargetPosition.positions){ - std::cout << std::round(pos*100)/100 << " "; + std::cout << std::round(pos*100)/100 << "\t"; } std::cout << std::endl; } @@ -108,12 +112,12 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server ArmMotor *currmotor = NULL; int currItr = 0; - std::cout << currPoint << " / " << goal->trajectory.points.size() << std::endl; + // std::cout << currPoint << " / " << goal->trajectory.points.size() << std::endl; currPoint++; for(const auto &joint : joints){ for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ double velocity = VELOCITY_MAX == 0.F ? JOINT_SAFETY_HOLD_SPEED : currTargetPosition.velocities[currItr]/VELOCITY_MAX; - std::cout << "config setpoint: " << currTargetPosition.positions[currItr] << ":" << velocity << std::endl; + // std::cout << "config setpoint: " << currTargetPosition.positions[currItr] << ":" << velocity << std::endl; joint->configSetpoint(i, currTargetPosition.positions[currItr], velocity); currItr++; } @@ -130,17 +134,17 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server for(const auto &joint : joints){ for(int k = 0; k < joint->getDegreesOfFreedom(); k++){ - if (joint->getMotor(k)->getMotorState() == MotorState::MOVING) { - std::cout << "Moving" << std::endl; - } else if (joint->getMotor(k)->getMotorState() == MotorState::RUN_TO_TARGET) { - std::cout << "Run to target" << std::endl; - } else if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { - std::cout << "Stalling" << std::endl; - } else if (joint->getMotor(k)->getMotorState() == MotorState::STOP) { - std::cout << "Stop" << std::endl; - } else { - std::cout << "Error" << std::endl; - } + // if (joint->getMotor(k)->getMotorState() == MotorState::MOVING) { + // std::cout << "Moving" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == MotorState::RUN_TO_TARGET) { + // std::cout << "Run to target" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { + // std::cout << "Stalling" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == MotorState::STOP) { + // std::cout << "Stop" << std::endl; + // } else { + // std::cout << "Error" << std::endl; + // } if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { std::cout << "ACS stall detected" << std::endl; @@ -198,6 +202,7 @@ void publishJointStates(const ros::TimerEvent &event){ js_msg.name = names; js_msg.position = positions; + js_msg.header.stamp = ros::Time::now(); // Publish the Joint State message jointStatePublisher.publish(js_msg); } @@ -231,15 +236,15 @@ auto main(int argc, char** argv) ->int std::cout << "init motors" << std::endl; // Initialize all Joints - joints.at(0) = std::make_unique(std::move(turntable_joint), n); - joints.at(1) = std::make_unique(std::move(shoulder_joint), n); - joints.at(2) = std::make_unique(std::move(elbowPitch_joint), n); - joints.at(3) = std::make_unique(std::move(elbowRoll_joint), n); + joints.at(3) = std::make_unique(std::move(turntable_joint), n); + joints.at(2) = std::make_unique(std::move(shoulder_joint), n); + joints.at(0) = std::make_unique(std::move(elbowPitch_joint), n); + joints.at(1) = std::make_unique(std::move(elbowRoll_joint), n); joints.at(4) = std::make_unique(std::move(wristPitch_joint), std::move(wristRoll_link), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); std::cout << "init joints" << std::endl; // Initialize the Joint State Data Publisher - jointStatePublisher = n.advertise("/control/arm_joint_states", MESSAGE_CACHE_SIZE); + jointStatePublisher = n.advertise("/joint_states", MESSAGE_CACHE_SIZE); // Initialize the Action Server Server server(n, "/arm_controller/follow_joint_trajectory", boost::bind(&execute, _1, &server), false); diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp index c0e2fc6d..de45e748 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ b/src/wr_control_drive_arm/src/ArmMotor.cpp @@ -46,9 +46,9 @@ void ArmMotor::storeEncoderVals(const Std_UInt32 &msg){ this->feedbackPub.publish(feedbackMsg); if(this->currState == MotorState::RUN_TO_TARGET){ - std::cout << "[2] motor " << motorName << " position " << (hasReachedTarget(this->target) ? "at target " : "not at target ") << this->target << ":" << this->encoderVal << std::endl; + // std::cout << "[2] motor " << motorName << " position " << (hasReachedTarget(this->target) ? "at target " : "not at target ") << this->target << ":" << this->encoderVal << std::endl; if(hasReachedTarget(this->target)){ - std::cout << "[1] stop motor" << std::endl; + // std::cout << "[1] stop motor" << std::endl; this->setPower(0.F, MotorState::STOP); } } @@ -115,19 +115,19 @@ auto ArmMotor::getEncoderCounts() const -> uint32_t{ } void ArmMotor::runToTarget(uint32_t targetCounts, float power){ - std::cout << "run to enc: " << targetCounts << std::endl; + // std::cout << "run to enc: " << targetCounts << std::endl; this->runToTarget(targetCounts, power, false); } auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool{ - std::cout << "TOLERANCE: " << tolerance << std::endl; + // std::cout << "TOLERANCE: " << tolerance << std::endl; // Compute the upper and lower bounds in the finite encoder space int32_t lBound = ArmMotor::corrMod(static_cast(targetCounts - tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); int32_t uBound = ArmMotor::corrMod(static_cast(targetCounts + tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); - std::cout << "LBOUND: " << (lBound) << " UBOUND: " << (uBound) << std::endl; + // std::cout << "LBOUND: " << (lBound) << " UBOUND: " << (uBound) << std::endl; auto position = ArmMotor::corrMod(getEncoderCounts(), ENCODER_BOUNDS[1]); - std::cout << "POSITION RAW: " << encToRad(getEncoderCounts()) << "/" << getEncoderCounts() << std::endl; - std::cout << "POSITION: " << encToRad(position) << "/" << position << std::endl; + // std::cout << "POSITION RAW: " << encToRad(getEncoderCounts()) << "/" << getEncoderCounts() << std::endl; + // std::cout << "POSITION: " << encToRad(position) << "/" << position << std::endl; // If the computed lower bound is lower than the upper bound, perform the computation normally if(lBound < uBound) return position <= uBound && position >=lBound; diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index e4278ebd..67744854 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -15,7 +15,7 @@ - +
diff --git a/src/wr_logic_teleop_arm/launch/std.launch b/src/wr_logic_teleop_arm/launch/std.launch index 64ff8e42..a5e0beaa 100644 --- a/src/wr_logic_teleop_arm/launch/std.launch +++ b/src/wr_logic_teleop_arm/launch/std.launch @@ -1,6 +1,7 @@ - + + diff --git a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp index 4793cbe2..5c1b684e 100644 --- a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp +++ b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp @@ -242,7 +242,7 @@ auto main(int argc, char** argv) -> int{ p.pose.position.y = y_pos; p.pose.position.z = z_pos; p.pose.orientation = tf2::toMsg(orientation); - p.header.frame_id = "odom_combined"; + p.header.frame_id = "world"; move.setPoseTarget(p); move.setStartStateToCurrentState(); @@ -250,7 +250,7 @@ auto main(int argc, char** argv) -> int{ //plan and execute path move.asyncMove(); - while(ros::ok){ + while(ros::ok()){ updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); if(move.getMoveGroupClient().getState().isDone()){ diff --git a/src/wroboarm_21/.setup_assistant b/src/wroboarm_21/.setup_assistant deleted file mode 100644 index 04da6248..00000000 --- a/src/wroboarm_21/.setup_assistant +++ /dev/null @@ -1,11 +0,0 @@ -moveit_setup_assistant_config: - URDF: - package: wroboarm_21 - relative_path: urdf/wroboarm_21.urdf - xacro_args: "" - SRDF: - relative_path: config/wroboarm_21.srdf - CONFIG: - author_name: me - author_email: me@me.me - generated_timestamp: 1615512414 \ No newline at end of file diff --git a/src/wroboarm_21/CMakeLists.txt b/src/wroboarm_21/CMakeLists.txt deleted file mode 100644 index 1fbbe71b..00000000 --- a/src/wroboarm_21/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -cmake_minimum_required(VERSION 3.1.3) -project(wroboarm_21) - -find_package(catkin REQUIRED) - -catkin_package() - -install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - PATTERN "setup_assistant.launch" EXCLUDE) -install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/src/wroboarm_21/config/cartesian_limits.yaml b/src/wroboarm_21/config/cartesian_limits.yaml deleted file mode 100644 index 7df72f69..00000000 --- a/src/wroboarm_21/config/cartesian_limits.yaml +++ /dev/null @@ -1,5 +0,0 @@ -cartesian_limits: - max_trans_vel: 1 - max_trans_acc: 2.25 - max_trans_dec: -5 - max_rot_vel: 1.57 diff --git a/src/wroboarm_21/config/chomp_planning.yaml b/src/wroboarm_21/config/chomp_planning.yaml deleted file mode 100644 index 75258e53..00000000 --- a/src/wroboarm_21/config/chomp_planning.yaml +++ /dev/null @@ -1,18 +0,0 @@ -planning_time_limit: 10.0 -max_iterations: 200 -max_iterations_after_collision_free: 5 -smoothness_cost_weight: 0.1 -obstacle_cost_weight: 1.0 -learning_rate: 0.01 -smoothness_cost_velocity: 0.0 -smoothness_cost_acceleration: 1.0 -smoothness_cost_jerk: 0.0 -ridge_factor: 0.01 -use_pseudo_inverse: false -pseudo_inverse_ridge_factor: 1e-4 -joint_update_limit: 0.1 -collision_clearence: 0.2 -collision_threshold: 0.07 -use_stochastic_descent: true -enable_failure_recovery: true -max_recovery_attempts: 5 \ No newline at end of file diff --git a/src/wroboarm_21/config/fake_controllers.yaml b/src/wroboarm_21/config/fake_controllers.yaml deleted file mode 100644 index e296f940..00000000 --- a/src/wroboarm_21/config/fake_controllers.yaml +++ /dev/null @@ -1,13 +0,0 @@ -controller_list: - - name: fake_arm_controller - joints: - - link1_joint - - link2_joint - - link3_joint - - link4_joint - - link5_joint - - link6_joint - - link7_joint -initial: # Define initial robot poses. - - group: arm -# pose: home diff --git a/src/wroboarm_21/config/joint_limits.yaml b/src/wroboarm_21/config/joint_limits.yaml deleted file mode 100644 index be8e07da..00000000 --- a/src/wroboarm_21/config/joint_limits.yaml +++ /dev/null @@ -1,45 +0,0 @@ -# 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: - link1_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - link2_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - link3_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - link4_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - link5_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - link6_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - link7_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 diff --git a/src/wroboarm_21/config/joint_names_wroboarm_21.yaml b/src/wroboarm_21/config/joint_names_wroboarm_21.yaml deleted file mode 100644 index fbfbe031..00000000 --- a/src/wroboarm_21/config/joint_names_wroboarm_21.yaml +++ /dev/null @@ -1 +0,0 @@ -controller_joint_names: ['', 'link1_joint', 'link2_joint', 'link3_joint', 'link4_joint', 'link5_joint', 'link6_joint', 'link7_joint', ] diff --git a/src/wroboarm_21/config/kinematics.yaml b/src/wroboarm_21/config/kinematics.yaml deleted file mode 100644 index 05573e5c..00000000 --- a/src/wroboarm_21/config/kinematics.yaml +++ /dev/null @@ -1,4 +0,0 @@ -arm: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 \ No newline at end of file diff --git a/src/wroboarm_21/config/ompl_planning.yaml b/src/wroboarm_21/config/ompl_planning.yaml deleted file mode 100644 index ce098a0c..00000000 --- a/src/wroboarm_21/config/ompl_planning.yaml +++ /dev/null @@ -1,156 +0,0 @@ -planner_configs: - AnytimePathShortening: - type: geometric::AnytimePathShortening - shortcut: true # Attempt to shortcut all new solution paths - hybridize: true # Compute hybrid solution trajectories - max_hybrid_paths: 24 # Number of hybrid paths generated per iteration - num_planners: 4 # The number of default planners to use for planning - planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - SBL: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - EST: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECE: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECE: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECE: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRT: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnect: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstar: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRT: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() - PRM: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstar: - type: geometric::PRMstar - FMT: - type: geometric::FMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 - nearest_k: 1 # use Knearest strategy. default: 1 - cache_cc: 1 # use collision checking cache. default: 1 - heuristics: 0 # activate cost to go heuristics. default: 0 - extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - BFMT: - type: geometric::BFMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 - nearest_k: 1 # use the Knearest strategy. default: 1 - balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 - optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 - heuristics: 1 # activates cost to go heuristics. default: 1 - cache_cc: 1 # use the collision checking cache. default: 1 - extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - PDST: - type: geometric::PDST - STRIDE: - type: geometric::STRIDE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 - degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 - max_degree: 18 # max degree of a node in the GNAT. default: 12 - min_degree: 12 # min degree of a node in the GNAT. default: 12 - max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 - estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 - min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 - BiTRRT: - type: geometric::BiTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 - init_temperature: 100 # initial temperature. default: 100 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf - LBTRRT: - type: geometric::LBTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - epsilon: 0.4 # optimality approximation factor. default: 0.4 - BiEST: - type: geometric::BiEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ProjEST: - type: geometric::ProjEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LazyPRM: - type: geometric::LazyPRM - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - LazyPRMstar: - type: geometric::LazyPRMstar - SPARS: - type: geometric::SPARS - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 1000 # maximum consecutive failure limit. default: 1000 - SPARStwo: - type: geometric::SPARStwo - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 5000 # maximum consecutive failure limit. default: 5000 -arm: - default_planner_config: RRTstar - planner_configs: - - AnytimePathShortening - - SBL - - EST - - LBKPIECE - - BKPIECE - - KPIECE - - RRT - - RRTConnect - - RRTstar - - TRRT - - PRM - - PRMstar - - FMT - - BFMT - - PDST - - STRIDE - - BiTRRT - - LBTRRT - - BiEST - - ProjEST - - LazyPRM - - LazyPRMstar - - SPARS - - SPARStwo \ No newline at end of file diff --git a/src/wroboarm_21/config/ros_controllers.yaml b/src/wroboarm_21/config/ros_controllers.yaml deleted file mode 100644 index ebdad9d2..00000000 --- a/src/wroboarm_21/config/ros_controllers.yaml +++ /dev/null @@ -1,37 +0,0 @@ -# Simulation settings for using moveit_sim_controllers -moveit_sim_hw_interface: - joint_model_group: todo_group_name - joint_model_group_pose: todo_state_name -# Settings for ros_control_boilerplate control loop -generic_hw_control_loop: - loop_hz: 300 - cycle_time_error_threshold: 0.01 -# Settings for ros_control hardware interface -hardware_interface: - joints: - - link1_joint - - link2_joint - - link3_joint - - link4_joint - - link5_joint - - link6_joint - - link7_joint - sim_control_mode: 1 # 0: position, 1: velocity -# Publish all joint states -# Creates the /joint_states topic necessary in ROS -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 50 -controller_list: - - name: arm_controller - action_ns: follow_joint_trajectory - default: True - type: FollowJointTrajectory - joints: - - link1_joint - - link2_joint - - link3_joint - - link4_joint - - link5_joint - - link6_joint - - link7_joint diff --git a/src/wroboarm_21/config/sensors_3d.yaml b/src/wroboarm_21/config/sensors_3d.yaml deleted file mode 100644 index a4bb13e3..00000000 --- a/src/wroboarm_21/config/sensors_3d.yaml +++ /dev/null @@ -1,10 +0,0 @@ -# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it -sensors: - - filtered_cloud_topic: filtered_cloud - max_range: 5.0 - max_update_rate: 1.0 - padding_offset: 0.1 - padding_scale: 1.0 - point_cloud_topic: /head_mount_kinect/depth_registered/points - point_subsample: 1 - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater \ No newline at end of file diff --git a/src/wroboarm_21/config/wroboarm_21.srdf b/src/wroboarm_21/config/wroboarm_21.srdf deleted file mode 100644 index cef5e442..00000000 --- a/src/wroboarm_21/config/wroboarm_21.srdf +++ /dev/null @@ -1,38 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/export.log b/src/wroboarm_21/export.log deleted file mode 100644 index 052f4f98..00000000 --- a/src/wroboarm_21/export.log +++ /dev/null @@ -1,365 +0,0 @@ -2020-12-21 21:22:47,283 INFO Logger.cs: 70 - --------------------------------------------------------------------------------- -2020-12-21 21:22:47,333 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter -2020-12-21 21:22:47,335 INFO Logger.cs: 73 - Commit version 1.6.0-1-g15f4949 -2020-12-21 21:22:47,336 INFO Logger.cs: 74 - Build version 1.6.7594.29634 -2020-12-21 21:22:47,339 INFO SwAddin.cs: 192 - Attempting to connect to SW -2020-12-21 21:22:47,340 INFO SwAddin.cs: 197 - Setting up callbacks -2020-12-21 21:22:47,341 INFO SwAddin.cs: 201 - Setting up command manager -2020-12-21 21:22:47,343 INFO SwAddin.cs: 204 - Adding command manager -2020-12-21 21:22:47,347 INFO SwAddin.cs: 263 - Adding Assembly export to file menu -2020-12-21 21:22:47,349 INFO SwAddin.cs: 272 - Adding Part export to file menu -2020-12-21 21:22:47,350 INFO SwAddin.cs: 210 - Adding event handlers -2020-12-21 21:22:47,354 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks -2020-12-21 21:24:27,526 INFO SwAddin.cs: 294 - Assembly export called for file wroboarm_21 -2020-12-21 21:24:29,650 INFO SwAddin.cs: 313 - Saving assembly -2020-12-21 21:24:29,826 INFO SwAddin.cs: 316 - Opening property manager -2020-12-21 21:24:29,876 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from wroboarm_21 -2020-12-21 21:24:29,891 INFO ExportHelperExtension.cs: 1136 - Found 59 in wroboarm_21 -2020-12-21 21:24:29,893 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in wroboarm_21 -2020-12-21 21:24:29,894 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2020-12-21 21:24:29,896 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2020-12-21 21:24:29,898 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forearm-1 -2020-12-21 21:24:29,900 INFO ExportHelperExtension.cs: 1136 - Found 31 in Forearm-1 -2020-12-21 21:24:29,901 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forearm-1 -2020-12-21 21:24:29,902 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elbow-1 -2020-12-21 21:24:29,904 INFO ExportHelperExtension.cs: 1136 - Found 27 in Elbow-1 -2020-12-21 21:24:29,905 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elbow-1 -2020-12-21 21:24:29,906 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from TurnTable-1 -2020-12-21 21:24:29,907 INFO ExportHelperExtension.cs: 1136 - Found 25 in TurnTable-1 -2020-12-21 21:24:29,908 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in TurnTable-1 -2020-12-21 21:24:29,909 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2020-12-21 21:24:29,910 INFO ExportHelperExtension.cs: 1136 - Found 27 in UpperArm-1 -2020-12-21 21:24:29,912 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2020-12-21 21:24:29,913 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2020-12-21 21:24:29,915 INFO ExportHelperExtension.cs: 1136 - Found 29 in Shoulder-1 -2020-12-21 21:24:29,916 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2020-12-21 21:24:29,917 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2020-12-21 21:24:29,918 INFO ExportHelperExtension.cs: 1136 - Found 27 in Manipulator-1 -2020-12-21 21:24:29,921 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2020-12-21 21:24:29,924 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2020-12-21 21:24:29,925 INFO ExportHelperExtension.cs: 1136 - Found 29 in Wrist-1 -2020-12-21 21:24:29,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2020-12-21 21:24:29,930 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from wroboarm_21 -2020-12-21 21:24:29,932 INFO ExportHelperExtension.cs: 1136 - Found 59 in wroboarm_21 -2020-12-21 21:24:29,934 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in wroboarm_21 -2020-12-21 21:24:29,935 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2020-12-21 21:24:29,936 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2020-12-21 21:24:29,937 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forearm-1 -2020-12-21 21:24:29,938 INFO ExportHelperExtension.cs: 1136 - Found 31 in Forearm-1 -2020-12-21 21:24:29,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forearm-1 -2020-12-21 21:24:29,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elbow-1 -2020-12-21 21:24:29,941 INFO ExportHelperExtension.cs: 1136 - Found 27 in Elbow-1 -2020-12-21 21:24:29,943 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elbow-1 -2020-12-21 21:24:29,944 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from TurnTable-1 -2020-12-21 21:24:29,945 INFO ExportHelperExtension.cs: 1136 - Found 25 in TurnTable-1 -2020-12-21 21:24:29,946 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in TurnTable-1 -2020-12-21 21:24:29,947 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2020-12-21 21:24:29,949 INFO ExportHelperExtension.cs: 1136 - Found 27 in UpperArm-1 -2020-12-21 21:24:29,950 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2020-12-21 21:24:29,952 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2020-12-21 21:24:29,953 INFO ExportHelperExtension.cs: 1136 - Found 29 in Shoulder-1 -2020-12-21 21:24:29,954 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2020-12-21 21:24:29,962 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2020-12-21 21:24:30,065 INFO ExportHelperExtension.cs: 1136 - Found 27 in Manipulator-1 -2020-12-21 21:24:30,066 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2020-12-21 21:24:30,068 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2020-12-21 21:24:30,070 INFO ExportHelperExtension.cs: 1136 - Found 29 in Wrist-1 -2020-12-21 21:24:30,071 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2020-12-21 21:24:30,351 INFO SwAddin.cs: 339 - Loading config tree -2020-12-21 21:24:30,360 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametrueturntablexyztrue-2.8254193696243868E-170-6.7465241345308752E-18rpytrue000originfalsefalsevaluetrue0.39680623003092352massfalseixxtrue0.00057145415023748434ixytrue0ixztrue2.2383483955223888E-21iyytrue0.0011002410492471767iyztrue0izztrue0.00057145415023748434inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametruegearboxxyztrue-6.8631413935065579E-180.03801532439663572-0.0013892205096921757rpytrue000originfalsefalsevaluetrue0.34120985304638518massfalseixxtrue0.00063726488338474081ixytrue7.0764513023917949E-20ixztrue-2.7252675378665934E-19iyytrue0.00083450439761804886iyztrue1.6294136810805574E-05izztrue0.00088931887892574886inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink1_jointtypetruecontinuousxyztrue000.0127rpytrue1.570800originfalsefalselinktrueturntableparenttruelinktruegearboxchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link1_joint2Origin_link1_joint2linktruenametrueupperarmxyztrue1.4123887173905075E-170.157206632847804122.7755575615628914E-17rpytrue000originfalsefalsevaluetrue1.264124215876306massfalseixxtrue0.013677990391055649ixytrue3.368445392332098E-19ixztrue3.9611983830710858E-20iyytrue0.000964387075304149iyztrue-2.6745670344635044E-18izztrue0.014091749673708917inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink2_jointtypetruecontinuousxyztrue00.072390.03683rpytrue000originfalsefalselinktruegearboxparenttruelinktrueupperarmchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link2_joint2Origin_link2_joint2linktruenametrueelbowxyztrue7.3321042375852733E-180.046279720003911486-0.0099170828579809855rpytrue000originfalsefalsevaluetrue0.625328404239412massfalseixxtrue0.0015093628788121875ixytrue7.2251958937028559E-20ixztrue2.6531119727066055E-20iyytrue0.00077150412582161528iyztrue-1.1346887107722466E-05izztrue0.0010232990551232335inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink3_jointtypetruecontinuousxyztrue00.3810rpytrue-1.570800originfalsefalselinktrueupperarmparenttruelinktrueelbowchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link3_jointOrigin_link3_jointlinktruenametrueforearmxyztrue-1.1893700871757326E-17-1.9081958235744878E-17-0.11306639219877124rpytrue000originfalsefalsevaluetrue0.46063240123192695massfalseixxtrue0.0022362056644483611ixytrue2.8623740668759855E-21ixztrue-6.9238813900453064E-20iyytrue0.0022468403158638628iyztrue-3.0218548775228389E-19izztrue0.00024560226807657237inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink4_jointtypetruecontinuousxyztrue00.044450.04445rpytrue3.141600originfalsefalselinktrueelbowparenttruelinktrueforearmchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link4_jointOrigin_link4_jointlinktruenametruewristxyztrue-7.1276563553462352E-097.8062556418956319E-18-3.4149891803281207E-09rpytrue000originfalsefalsevaluetrue0.064200890136229274massfalseixxtrue3.4980909309943769E-05ixytrue5.2887802729807491E-11ixztrue1.565944720011522E-18iyytrue2.4290927928157113E-05iyztrue-4.3708304367957221E-11izztrue2.8670971509987432E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink5_jointtypetruecontinuousxyztrue00-0.254rpytrue3.141600originfalsefalselinktrueforearmparenttruelinktruewristchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link5_jointOrigin_link5_jointlinktruenametruemanipulatorxyztrue3.4694469519536142E-189.8733856357333089E-18-0.038099999999999912rpytrue000originfalsefalsevaluetrue0.1580336580927709massfalseixxtrue0.00011719996250307502ixytrue2.2033040782480907E-21ixztrue2.5135101783302778E-20iyytrue0.00011719996250307503iyztrue8.5958526221282082E-21izztrue8.1464432723451653E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink6_jointtypetruecontinuousxyztrue000.0254rpytrue3.141601.5708originfalsefalselinktruewristparenttruelinktruemanipulatorchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link6_jointOrigin_link6_jointlinktruefalse4C4AAAUAAAD//v8XTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAA1AAAAfalsefalsefalse4C4AAAUAAAD//v8RVwByAGkAcwB0AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAxAAAAfalsefalsefalse4C4AAAUAAAD//v8TRgBvAHIAZQBhAHIAbQAtADEAQABTAGkAbQBwAGwAZQBBAHIAbQAEAAAAEAAAAAEAAAABAAAAKgAAAA==falsefalsefalse4C4AAAUAAAD//v8RRQBsAGIAbwB3AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAoAAAAfalsefalsefalse4C4AAAUAAAD//v8UVQBwAHAAZQByAEEAcgBtAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAaAAAAfalsefalsefalse4C4AAAUAAAD//v8UUwBoAG8AdQBsAGQAZQByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAYAAAAfalsefalsefalse4C4AAAUAAAD//v8VVAB1AHIAbgBUAGEAYgBsAGUALQAxAEAAUwBpAG0AcABsAGUAQQByAG0ABAAAABAAAAABAAAAAQAAABkAAAA=falsefalse -2020-12-21 21:24:30,482 INFO LinkNode.cs: 35 - Building node turntable -2020-12-21 21:24:30,484 INFO LinkNode.cs: 35 - Building node gearbox -2020-12-21 21:24:30,484 INFO LinkNode.cs: 35 - Building node upperarm -2020-12-21 21:24:30,485 INFO LinkNode.cs: 35 - Building node elbow -2020-12-21 21:24:30,485 INFO LinkNode.cs: 35 - Building node forearm -2020-12-21 21:24:30,486 INFO LinkNode.cs: 35 - Building node wrist -2020-12-21 21:24:30,486 INFO LinkNode.cs: 35 - Building node manipulator -2020-12-21 21:24:30,487 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for turntable from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,489 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???TurnTable-1@SimpleArm -2020-12-21 21:24:30,492 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\TurnTable.SLDPRT -2020-12-21 21:24:30,492 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link turntable -2020-12-21 21:24:30,493 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for gearbox from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,493 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???Shoulder-1@SimpleArm -2020-12-21 21:24:30,494 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Shoulder.SLDPRT -2020-12-21 21:24:30,494 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link gearbox -2020-12-21 21:24:30,494 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for upperarm from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,495 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???UpperArm-1@SimpleArm -2020-12-21 21:24:30,495 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\UpperArm.SLDPRT -2020-12-21 21:24:30,495 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link upperarm -2020-12-21 21:24:30,496 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for elbow from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,496 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???Elbow-1@SimpleArm( -2020-12-21 21:24:30,497 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Elbow.SLDPRT -2020-12-21 21:24:30,497 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link elbow -2020-12-21 21:24:30,497 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for forearm from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,498 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???Forearm-1@SimpleArm* -2020-12-21 21:24:30,498 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Forearm.SLDPRT -2020-12-21 21:24:30,498 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link forearm -2020-12-21 21:24:30,499 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for wrist from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,499 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???Wrist-1@SimpleArm1 -2020-12-21 21:24:30,500 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Wrist.SLDPRT -2020-12-21 21:24:30,500 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link wrist -2020-12-21 21:24:30,500 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for manipulator from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:24:30,501 INFO CommonSwOperations.cs: 245 - Loading component with PID ?.???Manipulator-1@SimpleArm5 -2020-12-21 21:24:30,501 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Manipulator.SLDPRT -2020-12-21 21:24:30,502 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link manipulator -2020-12-21 21:24:30,533 INFO SwAddin.cs: 344 - Showing property manager -2020-12-21 21:24:52,093 INFO ExportPropertyManager.cs: 422 - Configuration saved -2020-12-21 21:24:52,099 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametrueturntablexyztrue-2.8254193696243868E-170-6.7465241345308752E-18rpytrue000originfalsefalsevaluetrue0.39680623003092352massfalseixxtrue0.00057145415023748434ixytrue0ixztrue2.2383483955223888E-21iyytrue0.0011002410492471767iyztrue0izztrue0.00057145415023748434inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametruegearboxxyztrue-6.8631413935065579E-180.03801532439663572-0.0013892205096921757rpytrue000originfalsefalsevaluetrue0.34120985304638518massfalseixxtrue0.00063726488338474081ixytrue7.0764513023917949E-20ixztrue-2.7252675378665934E-19iyytrue0.00083450439761804886iyztrue1.6294136810805574E-05izztrue0.00088931887892574886inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink1_jointtypetruecontinuousxyztrue000.0127rpytrue1.570800originfalsefalselinktrueturntableparenttruelinktruegearboxchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link1_joint2Origin_link1_joint2linktruenametrueupperarmxyztrue1.4123887173905075E-170.157206632847804122.7755575615628914E-17rpytrue000originfalsefalsevaluetrue1.264124215876306massfalseixxtrue0.013677990391055649ixytrue3.368445392332098E-19ixztrue3.9611983830710858E-20iyytrue0.000964387075304149iyztrue-2.6745670344635044E-18izztrue0.014091749673708917inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink2_jointtypetruecontinuousxyztrue00.072390.03683rpytrue000originfalsefalselinktruegearboxparenttruelinktrueupperarmchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link2_joint2Origin_link2_joint2linktruenametrueelbowxyztrue7.3321042375852733E-180.046279720003911486-0.0099170828579809855rpytrue000originfalsefalsevaluetrue0.625328404239412massfalseixxtrue0.0015093628788121875ixytrue7.2251958937028559E-20ixztrue2.6531119727066055E-20iyytrue0.00077150412582161528iyztrue-1.1346887107722466E-05izztrue0.0010232990551232335inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink3_jointtypetruecontinuousxyztrue00.3810rpytrue-1.570800originfalsefalselinktrueupperarmparenttruelinktrueelbowchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link3_jointOrigin_link3_jointlinktruenametrueforearmxyztrue-1.1893700871757326E-17-1.9081958235744878E-17-0.11306639219877124rpytrue000originfalsefalsevaluetrue0.46063240123192695massfalseixxtrue0.0022362056644483611ixytrue2.8623740668759855E-21ixztrue-6.9238813900453064E-20iyytrue0.0022468403158638628iyztrue-3.0218548775228389E-19izztrue0.00024560226807657237inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink4_jointtypetruecontinuousxyztrue00.044450.04445rpytrue3.141600originfalsefalselinktrueelbowparenttruelinktrueforearmchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link4_jointOrigin_link4_jointlinktruenametruewristxyztrue-7.1276563553462352E-097.8062556418956319E-18-3.4149891803281207E-09rpytrue000originfalsefalsevaluetrue0.064200890136229274massfalseixxtrue3.4980909309943769E-05ixytrue5.2887802729807491E-11ixztrue1.565944720011522E-18iyytrue2.4290927928157113E-05iyztrue-4.3708304367957221E-11izztrue2.8670971509987432E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink5_jointtypetruecontinuousxyztrue00-0.254rpytrue3.141600originfalsefalselinktrueforearmparenttruelinktruewristchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link5_jointOrigin_link5_jointlinktruenametruemanipulatorxyztrue3.4694469519536142E-189.8733856357333089E-18-0.038099999999999912rpytrue000originfalsefalsevaluetrue0.1580336580927709massfalseixxtrue0.00011719996250307502ixytrue2.2033040782480907E-21ixztrue2.5135101783302778E-20iyytrue0.00011719996250307503iyztrue8.5958526221282082E-21izztrue8.1464432723451653E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink6_jointtypetruecontinuousxyztrue000.0254rpytrue3.141601.5708originfalsefalselinktruewristparenttruelinktruemanipulatorchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link6_jointOrigin_link6_jointlinktruefalse4C4AAAUAAAD//v8XTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAA1AAAAfalsefalsefalse4C4AAAUAAAD//v8RVwByAGkAcwB0AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAxAAAAfalsefalsefalse4C4AAAUAAAD//v8TRgBvAHIAZQBhAHIAbQAtADEAQABTAGkAbQBwAGwAZQBBAHIAbQAEAAAAEAAAAAEAAAABAAAAKgAAAA==falsefalsefalse4C4AAAUAAAD//v8RRQBsAGIAbwB3AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAoAAAAfalsefalsefalse4C4AAAUAAAD//v8UVQBwAHAAZQByAEEAcgBtAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAaAAAAfalsefalsefalse4C4AAAUAAAD//v8UUwBoAG8AdQBsAGQAZQByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAYAAAAfalsefalsefalse4C4AAAUAAAD//v8VVAB1AHIAbgBUAGEAYgBsAGUALQAxAEAAUwBpAG0AcABsAGUAQQByAG0ABAAAABAAAAABAAAAAQAAABkAAAA=falsefalse -2020-12-21 21:24:52,272 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2020-12-21 21:26:19,586 INFO SwAddin.cs: 294 - Assembly export called for file wroboarm_21 -2020-12-21 21:26:19,586 INFO SwAddin.cs: 299 - Save is required -2020-12-21 21:26:19,587 INFO SwAddin.cs: 313 - Saving assembly -2020-12-21 21:26:20,090 INFO SwAddin.cs: 316 - Opening property manager -2020-12-21 21:26:20,091 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from wroboarm_21 -2020-12-21 21:26:20,092 INFO ExportHelperExtension.cs: 1136 - Found 59 in wroboarm_21 -2020-12-21 21:26:20,093 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in wroboarm_21 -2020-12-21 21:26:20,094 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2020-12-21 21:26:20,095 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2020-12-21 21:26:20,096 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forearm-1 -2020-12-21 21:26:20,097 INFO ExportHelperExtension.cs: 1136 - Found 31 in Forearm-1 -2020-12-21 21:26:20,098 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forearm-1 -2020-12-21 21:26:20,099 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elbow-1 -2020-12-21 21:26:20,100 INFO ExportHelperExtension.cs: 1136 - Found 27 in Elbow-1 -2020-12-21 21:26:20,101 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elbow-1 -2020-12-21 21:26:20,103 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from TurnTable-1 -2020-12-21 21:26:20,104 INFO ExportHelperExtension.cs: 1136 - Found 25 in TurnTable-1 -2020-12-21 21:26:20,105 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in TurnTable-1 -2020-12-21 21:26:20,106 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2020-12-21 21:26:20,108 INFO ExportHelperExtension.cs: 1136 - Found 27 in UpperArm-1 -2020-12-21 21:26:20,109 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2020-12-21 21:26:20,110 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2020-12-21 21:26:20,111 INFO ExportHelperExtension.cs: 1136 - Found 29 in Shoulder-1 -2020-12-21 21:26:20,113 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2020-12-21 21:26:20,115 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2020-12-21 21:26:20,116 INFO ExportHelperExtension.cs: 1136 - Found 27 in Manipulator-1 -2020-12-21 21:26:20,122 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2020-12-21 21:26:20,123 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2020-12-21 21:26:20,125 INFO ExportHelperExtension.cs: 1136 - Found 29 in Wrist-1 -2020-12-21 21:26:20,127 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2020-12-21 21:26:20,128 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from wroboarm_21 -2020-12-21 21:26:20,129 INFO ExportHelperExtension.cs: 1136 - Found 59 in wroboarm_21 -2020-12-21 21:26:20,130 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in wroboarm_21 -2020-12-21 21:26:20,133 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2020-12-21 21:26:20,134 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2020-12-21 21:26:20,135 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forearm-1 -2020-12-21 21:26:20,136 INFO ExportHelperExtension.cs: 1136 - Found 31 in Forearm-1 -2020-12-21 21:26:20,137 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forearm-1 -2020-12-21 21:26:20,138 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elbow-1 -2020-12-21 21:26:20,139 INFO ExportHelperExtension.cs: 1136 - Found 27 in Elbow-1 -2020-12-21 21:26:20,149 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elbow-1 -2020-12-21 21:26:20,151 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from TurnTable-1 -2020-12-21 21:26:20,231 INFO ExportHelperExtension.cs: 1136 - Found 25 in TurnTable-1 -2020-12-21 21:26:20,233 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in TurnTable-1 -2020-12-21 21:26:20,234 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2020-12-21 21:26:20,235 INFO ExportHelperExtension.cs: 1136 - Found 27 in UpperArm-1 -2020-12-21 21:26:20,238 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2020-12-21 21:26:20,239 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2020-12-21 21:26:20,240 INFO ExportHelperExtension.cs: 1136 - Found 29 in Shoulder-1 -2020-12-21 21:26:20,241 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2020-12-21 21:26:20,242 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2020-12-21 21:26:20,243 INFO ExportHelperExtension.cs: 1136 - Found 27 in Manipulator-1 -2020-12-21 21:26:20,244 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2020-12-21 21:26:20,244 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2020-12-21 21:26:20,247 INFO ExportHelperExtension.cs: 1136 - Found 29 in Wrist-1 -2020-12-21 21:26:20,248 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2020-12-21 21:26:20,353 INFO SwAddin.cs: 339 - Loading config tree -2020-12-21 21:26:20,357 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametrueturntablexyztrue-2.8254193696243868E-170-6.7465241345308752E-18rpytrue000originfalsefalsevaluetrue0.39680623003092352massfalseixxtrue0.00057145415023748434ixytrue0ixztrue2.2383483955223888E-21iyytrue0.0011002410492471767iyztrue0izztrue0.00057145415023748434inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametruegearboxxyztrue-6.8631413935065579E-180.03801532439663572-0.0013892205096921757rpytrue000originfalsefalsevaluetrue0.34120985304638518massfalseixxtrue0.00063726488338474081ixytrue7.0764513023917949E-20ixztrue-2.7252675378665934E-19iyytrue0.00083450439761804886iyztrue1.6294136810805574E-05izztrue0.00088931887892574886inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink1_jointtypetruecontinuousxyztrue000.0127rpytrue1.570800originfalsefalselinktrueturntableparenttruelinktruegearboxchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueupperarmxyztrue1.4123887173905075E-170.157206632847804122.7755575615628914E-17rpytrue000originfalsefalsevaluetrue1.264124215876306massfalseixxtrue0.013677990391055649ixytrue3.368445392332098E-19ixztrue3.9611983830710858E-20iyytrue0.000964387075304149iyztrue-2.6745670344635044E-18izztrue0.014091749673708917inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink2_jointtypetruecontinuousxyztrue00.072390.03683rpytrue000originfalsefalselinktruegearboxparenttruelinktrueupperarmchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueelbowxyztrue7.3321042375852733E-180.046279720003911486-0.0099170828579809855rpytrue000originfalsefalsevaluetrue0.625328404239412massfalseixxtrue0.0015093628788121875ixytrue7.2251958937028559E-20ixztrue2.6531119727066055E-20iyytrue0.00077150412582161528iyztrue-1.1346887107722466E-05izztrue0.0010232990551232335inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink3_jointtypetruecontinuousxyztrue00.3810rpytrue-1.570800originfalsefalselinktrueupperarmparenttruelinktrueelbowchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link3_jointOrigin_link3_jointlinktruenametrueforearmxyztrue-1.1893700871757326E-17-1.9081958235744878E-17-0.11306639219877124rpytrue000originfalsefalsevaluetrue0.46063240123192695massfalseixxtrue0.0022362056644483611ixytrue2.8623740668759855E-21ixztrue-6.9238813900453064E-20iyytrue0.0022468403158638628iyztrue-3.0218548775228389E-19izztrue0.00024560226807657237inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink4_jointtypetruecontinuousxyztrue00.044450.04445rpytrue3.141600originfalsefalselinktrueelbowparenttruelinktrueforearmchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link4_jointOrigin_link4_jointlinktruenametruewristxyztrue-7.1276563553462352E-097.8062556418956319E-18-3.4149891803281207E-09rpytrue000originfalsefalsevaluetrue0.064200890136229274massfalseixxtrue3.4980909309943769E-05ixytrue5.2887802729807491E-11ixztrue1.565944720011522E-18iyytrue2.4290927928157113E-05iyztrue-4.3708304367957221E-11izztrue2.8670971509987432E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink5_jointtypetruecontinuousxyztrue00-0.254rpytrue3.141600originfalsefalselinktrueforearmparenttruelinktruewristchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link5_jointOrigin_link5_jointlinktruenametruemanipulatorxyztrue3.4694469519536142E-189.8733856357333089E-18-0.038099999999999912rpytrue000originfalsefalsevaluetrue0.1580336580927709massfalseixxtrue0.00011719996250307502ixytrue2.2033040782480907E-21ixztrue2.5135101783302778E-20iyytrue0.00011719996250307503iyztrue8.5958526221282082E-21izztrue8.1464432723451653E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink6_jointtypetruecontinuousxyztrue000.0254rpytrue3.141601.5708originfalsefalselinktruewristparenttruelinktruemanipulatorchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link6_jointOrigin_link6_jointlinktruefalseyDIAAAUAAAD//v8XTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAA1AAAAfalsefalsefalseyDIAAAUAAAD//v8RVwByAGkAcwB0AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAxAAAAfalsefalsefalseyDIAAAUAAAD//v8TRgBvAHIAZQBhAHIAbQAtADEAQABTAGkAbQBwAGwAZQBBAHIAbQAEAAAAEAAAAAEAAAABAAAAKgAAAA==falsefalsefalseyDIAAAUAAAD//v8RRQBsAGIAbwB3AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAoAAAAfalsefalsefalseyDIAAAUAAAD//v8UVQBwAHAAZQByAEEAcgBtAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAaAAAAfalsefalsefalseyDIAAAUAAAD//v8UUwBoAG8AdQBsAGQAZQByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAYAAAAfalsefalsefalseyDIAAAUAAAD//v8VVAB1AHIAbgBUAGEAYgBsAGUALQAxAEAAUwBpAG0AcABsAGUAQQByAG0ABAAAABAAAAABAAAAAQAAABkAAAA=falsefalse -2020-12-21 21:26:20,365 INFO LinkNode.cs: 35 - Building node turntable -2020-12-21 21:26:20,366 INFO LinkNode.cs: 35 - Building node gearbox -2020-12-21 21:26:20,366 INFO LinkNode.cs: 35 - Building node upperarm -2020-12-21 21:26:20,367 INFO LinkNode.cs: 35 - Building node elbow -2020-12-21 21:26:20,368 INFO LinkNode.cs: 35 - Building node forearm -2020-12-21 21:26:20,369 INFO LinkNode.cs: 35 - Building node wrist -2020-12-21 21:26:20,369 INFO LinkNode.cs: 35 - Building node manipulator -2020-12-21 21:26:20,370 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for turntable from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,371 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???TurnTable-1@SimpleArm -2020-12-21 21:26:20,372 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\TurnTable.SLDPRT -2020-12-21 21:26:20,373 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link turntable -2020-12-21 21:26:20,374 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for gearbox from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,374 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???Shoulder-1@SimpleArm -2020-12-21 21:26:20,376 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Shoulder.SLDPRT -2020-12-21 21:26:20,376 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link gearbox -2020-12-21 21:26:20,377 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for upperarm from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,378 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???UpperArm-1@SimpleArm -2020-12-21 21:26:20,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\UpperArm.SLDPRT -2020-12-21 21:26:20,381 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link upperarm -2020-12-21 21:26:20,381 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for elbow from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,382 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???Elbow-1@SimpleArm( -2020-12-21 21:26:20,383 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Elbow.SLDPRT -2020-12-21 21:26:20,384 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link elbow -2020-12-21 21:26:20,385 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for forearm from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,386 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???Forearm-1@SimpleArm* -2020-12-21 21:26:20,387 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Forearm.SLDPRT -2020-12-21 21:26:20,388 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link forearm -2020-12-21 21:26:20,390 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for wrist from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,391 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???Wrist-1@SimpleArm1 -2020-12-21 21:26:20,392 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Wrist.SLDPRT -2020-12-21 21:26:20,393 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link wrist -2020-12-21 21:26:20,395 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for manipulator from C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\wroboarm_21.SLDASM -2020-12-21 21:26:20,395 INFO CommonSwOperations.cs: 245 - Loading component with PID ?2???Manipulator-1@SimpleArm5 -2020-12-21 21:26:20,397 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\ustuner\Desktop\GrabCAD\WRover20\am_system\am_resources\IK Model\Manipulator.SLDPRT -2020-12-21 21:26:20,398 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link manipulator -2020-12-21 21:26:20,427 INFO SwAddin.cs: 344 - Showing property manager -2020-12-21 21:26:35,601 INFO ExportPropertyManager.cs: 422 - Configuration saved -2020-12-21 21:26:35,603 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametrueturntablexyztrue-2.8254193696243868E-170-6.7465241345308752E-18rpytrue000originfalsefalsevaluetrue0.39680623003092352massfalseixxtrue0.00057145415023748434ixytrue0ixztrue2.2383483955223888E-21iyytrue0.0011002410492471767iyztrue0izztrue0.00057145415023748434inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametruegearboxxyztrue-6.8631413935065579E-180.03801532439663572-0.0013892205096921757rpytrue000originfalsefalsevaluetrue0.34120985304638518massfalseixxtrue0.00063726488338474081ixytrue7.0764513023917949E-20ixztrue-2.7252675378665934E-19iyytrue0.00083450439761804886iyztrue1.6294136810805574E-05izztrue0.00088931887892574886inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink1_jointtypetruecontinuousxyztrue000.0127rpytrue1.570800originfalsefalselinktrueturntableparenttruelinktruegearboxchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueupperarmxyztrue1.4123887173905075E-170.157206632847804122.7755575615628914E-17rpytrue000originfalsefalsevaluetrue1.264124215876306massfalseixxtrue0.013677990391055649ixytrue3.368445392332098E-19ixztrue3.9611983830710858E-20iyytrue0.000964387075304149iyztrue-2.6745670344635044E-18izztrue0.014091749673708917inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink2_jointtypetruecontinuousxyztrue00.072390.03683rpytrue000originfalsefalselinktruegearboxparenttruelinktrueupperarmchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueelbowxyztrue7.3321042375852733E-180.046279720003911486-0.0099170828579809855rpytrue000originfalsefalsevaluetrue0.625328404239412massfalseixxtrue0.0015093628788121875ixytrue7.2251958937028559E-20ixztrue2.6531119727066055E-20iyytrue0.00077150412582161528iyztrue-1.1346887107722466E-05izztrue0.0010232990551232335inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink3_jointtypetruecontinuousxyztrue00.3810rpytrue-1.570800originfalsefalselinktrueupperarmparenttruelinktrueelbowchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link3_jointOrigin_link3_jointlinktruenametrueforearmxyztrue-1.1893700871757326E-17-1.9081958235744878E-17-0.11306639219877124rpytrue000originfalsefalsevaluetrue0.46063240123192695massfalseixxtrue0.0022362056644483611ixytrue2.8623740668759855E-21ixztrue-6.9238813900453064E-20iyytrue0.0022468403158638628iyztrue-3.0218548775228389E-19izztrue0.00024560226807657237inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink4_jointtypetruecontinuousxyztrue00.044450.04445rpytrue3.141600originfalsefalselinktrueelbowparenttruelinktrueforearmchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link4_jointOrigin_link4_jointlinktruenametruewristxyztrue-7.1276563553462352E-097.8062556418956319E-18-3.4149891803281207E-09rpytrue000originfalsefalsevaluetrue0.064200890136229274massfalseixxtrue3.4980909309943769E-05ixytrue5.2887802729807491E-11ixztrue1.565944720011522E-18iyytrue2.4290927928157113E-05iyztrue-4.3708304367957221E-11izztrue2.8670971509987432E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink5_jointtypetruecontinuousxyztrue00-0.254rpytrue3.141600originfalsefalselinktrueforearmparenttruelinktruewristchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link5_jointOrigin_link5_jointlinktruenametruemanipulatorxyztrue3.4694469519536142E-189.8733856357333089E-18-0.038099999999999912rpytrue000originfalsefalsevaluetrue0.1580336580927709massfalseixxtrue0.00011719996250307502ixytrue2.2033040782480907E-21ixztrue2.5135101783302778E-20iyytrue0.00011719996250307503iyztrue8.5958526221282082E-21izztrue8.1464432723451653E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink6_jointtypetruecontinuousxyztrue000.0254rpytrue3.141601.5708originfalsefalselinktruewristparenttruelinktruemanipulatorchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link6_jointOrigin_link6_jointlinktruefalseyDIAAAUAAAD//v8XTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAA1AAAAfalsefalsefalseyDIAAAUAAAD//v8RVwByAGkAcwB0AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAxAAAAfalsefalsefalseyDIAAAUAAAD//v8TRgBvAHIAZQBhAHIAbQAtADEAQABTAGkAbQBwAGwAZQBBAHIAbQAEAAAAEAAAAAEAAAABAAAAKgAAAA==falsefalsefalseyDIAAAUAAAD//v8RRQBsAGIAbwB3AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAoAAAAfalsefalsefalseyDIAAAUAAAD//v8UVQBwAHAAZQByAEEAcgBtAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAaAAAAfalsefalsefalseyDIAAAUAAAD//v8UUwBoAG8AdQBsAGQAZQByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAYAAAAfalsefalsefalseyDIAAAUAAAD//v8VVAB1AHIAbgBUAGEAYgBsAGUALQAxAEAAUwBpAG0AcABsAGUAQQByAG0ABAAAABAAAAABAAAAAQAAABkAAAA=falsefalse -2020-12-21 21:26:35,744 INFO ExportHelperExtension.cs: 347 - Creating joint gearbox -2020-12-21 21:26:35,753 INFO ExportHelperExtension.cs: 1397 - Fixing components for turntable -2020-12-21 21:26:35,754 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2020-12-21 21:26:36,153 INFO : 0 - R1: 1, System.__ComObject, 1, System.Double[] -2020-12-21 21:26:36,158 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2020-12-21 21:26:36,158 INFO ExportHelperExtension.cs: 849 - L1: 0 -2020-12-21 21:26:36,159 INFO ExportHelperExtension.cs: 857 - L2: 0 -2020-12-21 21:26:36,298 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2020-12-21 21:26:39,178 WARN ExportHelperExtension.cs: 351 - Creating joint from parent turntable to child gearbox failed -2020-12-21 21:26:39,185 INFO ExportHelperExtension.cs: 347 - Creating joint upperarm -2020-12-21 21:26:39,186 INFO ExportHelperExtension.cs: 1397 - Fixing components for gearbox -2020-12-21 21:26:39,186 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2020-12-21 21:26:39,186 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2020-12-21 21:26:39,481 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2020-12-21 21:26:39,482 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2020-12-21 21:26:39,483 INFO ExportHelperExtension.cs: 849 - L1: 0 -2020-12-21 21:26:39,483 INFO ExportHelperExtension.cs: 857 - L2: 0 -2020-12-21 21:26:39,484 INFO ExportHelperExtension.cs: 1352 - Unfixing component 24 -2020-12-21 21:26:39,484 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2020-12-21 21:26:42,112 WARN ExportHelperExtension.cs: 351 - Creating joint from parent gearbox to child upperarm failed -2020-12-21 21:26:42,118 INFO ExportHelperExtension.cs: 347 - Creating joint elbow -2020-12-21 21:26:42,166 WARN ExportHelperExtension.cs: 351 - Creating joint from parent upperarm to child elbow failed -2020-12-21 21:26:42,172 INFO ExportHelperExtension.cs: 347 - Creating joint forearm -2020-12-21 21:26:42,224 WARN ExportHelperExtension.cs: 351 - Creating joint from parent elbow to child forearm failed -2020-12-21 21:26:42,231 INFO ExportHelperExtension.cs: 347 - Creating joint wrist -2020-12-21 21:26:42,283 WARN ExportHelperExtension.cs: 351 - Creating joint from parent forearm to child wrist failed -2020-12-21 21:26:42,290 INFO ExportHelperExtension.cs: 347 - Creating joint manipulator -2020-12-21 21:26:42,346 WARN ExportHelperExtension.cs: 351 - Creating joint from parent wrist to child manipulator failed -2020-12-21 21:26:42,543 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from wroboarm_21 -2020-12-21 21:26:42,552 INFO ExportHelperExtension.cs: 1136 - Found 63 in wroboarm_21 -2020-12-21 21:26:42,553 INFO ExportHelperExtension.cs: 1145 - Found 9 features of type [CoordSys] in wroboarm_21 -2020-12-21 21:26:42,554 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2020-12-21 21:26:42,554 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2020-12-21 21:26:42,554 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forearm-1 -2020-12-21 21:26:42,555 INFO ExportHelperExtension.cs: 1136 - Found 31 in Forearm-1 -2020-12-21 21:26:42,555 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forearm-1 -2020-12-21 21:26:42,556 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elbow-1 -2020-12-21 21:26:42,556 INFO ExportHelperExtension.cs: 1136 - Found 27 in Elbow-1 -2020-12-21 21:26:42,557 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elbow-1 -2020-12-21 21:26:42,557 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from TurnTable-1 -2020-12-21 21:26:42,558 INFO ExportHelperExtension.cs: 1136 - Found 25 in TurnTable-1 -2020-12-21 21:26:42,558 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in TurnTable-1 -2020-12-21 21:26:42,559 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2020-12-21 21:26:42,560 INFO ExportHelperExtension.cs: 1136 - Found 27 in UpperArm-1 -2020-12-21 21:26:42,560 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2020-12-21 21:26:42,561 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2020-12-21 21:26:42,561 INFO ExportHelperExtension.cs: 1136 - Found 29 in Shoulder-1 -2020-12-21 21:26:42,562 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2020-12-21 21:26:42,562 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2020-12-21 21:26:42,563 INFO ExportHelperExtension.cs: 1136 - Found 27 in Manipulator-1 -2020-12-21 21:26:42,563 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2020-12-21 21:26:42,563 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2020-12-21 21:26:42,564 INFO ExportHelperExtension.cs: 1136 - Found 29 in Wrist-1 -2020-12-21 21:26:42,564 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2020-12-21 21:26:42,565 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from wroboarm_21 -2020-12-21 21:26:42,565 INFO ExportHelperExtension.cs: 1136 - Found 63 in wroboarm_21 -2020-12-21 21:26:42,566 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [RefAxis] in wroboarm_21 -2020-12-21 21:26:42,566 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2020-12-21 21:26:42,569 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2020-12-21 21:26:42,570 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forearm-1 -2020-12-21 21:26:42,598 INFO ExportHelperExtension.cs: 1136 - Found 31 in Forearm-1 -2020-12-21 21:26:42,599 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forearm-1 -2020-12-21 21:26:42,599 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elbow-1 -2020-12-21 21:26:42,599 INFO ExportHelperExtension.cs: 1136 - Found 27 in Elbow-1 -2020-12-21 21:26:42,599 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elbow-1 -2020-12-21 21:26:42,600 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from TurnTable-1 -2020-12-21 21:26:42,600 INFO ExportHelperExtension.cs: 1136 - Found 25 in TurnTable-1 -2020-12-21 21:26:42,601 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in TurnTable-1 -2020-12-21 21:26:42,601 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2020-12-21 21:26:42,602 INFO ExportHelperExtension.cs: 1136 - Found 27 in UpperArm-1 -2020-12-21 21:26:42,602 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2020-12-21 21:26:42,603 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2020-12-21 21:26:42,603 INFO ExportHelperExtension.cs: 1136 - Found 29 in Shoulder-1 -2020-12-21 21:26:42,604 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2020-12-21 21:26:42,604 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2020-12-21 21:26:42,605 INFO ExportHelperExtension.cs: 1136 - Found 27 in Manipulator-1 -2020-12-21 21:26:42,605 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2020-12-21 21:26:42,606 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2020-12-21 21:26:42,608 INFO ExportHelperExtension.cs: 1136 - Found 29 in Wrist-1 -2020-12-21 21:26:42,609 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2020-12-21 21:26:42,695 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2020-12-21 21:27:18,266 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2020-12-21 21:27:18,273 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametrueturntablexyztrue-2.8254193696243868E-170-6.7465241345308752E-18rpytrue000originfalsefalsevaluetrue0.39680623003092352massfalseixxtrue0.00057145415023748434ixytrue0ixztrue2.2383483955223888E-21iyytrue0.0011002410492471767iyztrue0izztrue0.00057145415023748434inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametruegearboxxyztrue-6.8631413935065579E-180.03801532439663572-0.0013892205096921757rpytrue000originfalsefalsevaluetrue0.34120985304638518massfalseixxtrue0.00063726488338474081ixytrue7.0764513023917949E-20ixztrue-2.7252675378665934E-19iyytrue0.00083450439761804886iyztrue1.6294136810805574E-05izztrue0.00088931887892574886inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink1_jointtypetruecontinuousxyztrue000.0127rpytrue1.570800originfalsefalselinktrueturntableparenttruelinktruegearboxchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueupperarmxyztrue1.4123887173905075E-170.157206632847804122.7755575615628914E-17rpytrue000originfalsefalsevaluetrue1.264124215876306massfalseixxtrue0.013677990391055649ixytrue3.368445392332098E-19ixztrue3.9611983830710858E-20iyytrue0.000964387075304149iyztrue-2.6745670344635044E-18izztrue0.014091749673708917inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink2_jointtypetruecontinuousxyztrue00.072390.03683rpytrue000originfalsefalselinktruegearboxparenttruelinktrueupperarmchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueelbowxyztrue7.3321042375852733E-180.046279720003911486-0.0099170828579809855rpytrue000originfalsefalsevaluetrue0.625328404239412massfalseixxtrue0.0015093628788121875ixytrue7.2251958937028559E-20ixztrue2.6531119727066055E-20iyytrue0.00077150412582161528iyztrue-1.1346887107722466E-05izztrue0.0010232990551232335inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink3_jointtypetruecontinuousxyztrue00.3810rpytrue-1.570800originfalsefalselinktrueupperarmparenttruelinktrueelbowchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link3_jointOrigin_link3_jointlinktruenametrueforearmxyztrue-1.1893700871757326E-17-1.9081958235744878E-17-0.11306639219877124rpytrue000originfalsefalsevaluetrue0.46063240123192695massfalseixxtrue0.0022362056644483611ixytrue2.8623740668759855E-21ixztrue-6.9238813900453064E-20iyytrue0.0022468403158638628iyztrue-3.0218548775228389E-19izztrue0.00024560226807657237inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink4_jointtypetruecontinuousxyztrue00.044450.04445rpytrue3.141600originfalsefalselinktrueelbowparenttruelinktrueforearmchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link4_jointOrigin_link4_jointlinktruenametruewristxyztrue-7.1276563553462352E-097.8062556418956319E-18-3.4149891803281207E-09rpytrue000originfalsefalsevaluetrue0.064200890136229274massfalseixxtrue3.4980909309943769E-05ixytrue5.2887802729807491E-11ixztrue1.565944720011522E-18iyytrue2.4290927928157113E-05iyztrue-4.3708304367957221E-11izztrue2.8670971509987432E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink5_jointtypetruecontinuousxyztrue00-0.254rpytrue3.141600originfalsefalselinktrueforearmparenttruelinktruewristchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link5_jointOrigin_link5_jointlinktruenametruemanipulatorxyztrue3.4694469519536142E-189.8733856357333089E-18-0.038099999999999912rpytrue000originfalsefalsevaluetrue0.1580336580927709massfalseixxtrue0.00011719996250307502ixytrue2.2033040782480907E-21ixztrue2.5135101783302778E-20iyytrue0.00011719996250307503iyztrue8.5958526221282082E-21izztrue8.1464432723451653E-05inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruelink6_jointtypetruecontinuousxyztrue000.0254rpytrue3.141601.5708originfalsefalselinktruewristparenttruelinktruemanipulatorchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upperfalsesoft_lowerfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_link6_jointOrigin_link6_jointlinktruefalseyDIAAAUAAAD//v8XTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAA1AAAAfalsefalsefalseyDIAAAUAAAD//v8RVwByAGkAcwB0AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAxAAAAfalsefalsefalseyDIAAAUAAAD//v8TRgBvAHIAZQBhAHIAbQAtADEAQABTAGkAbQBwAGwAZQBBAHIAbQAEAAAAEAAAAAEAAAABAAAAKgAAAA==falsefalsefalseyDIAAAUAAAD//v8RRQBsAGIAbwB3AC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAoAAAAfalsefalsefalseyDIAAAUAAAD//v8UVQBwAHAAZQByAEEAcgBtAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAaAAAAfalsefalsefalseyDIAAAUAAAD//v8UUwBoAG8AdQBsAGQAZQByAC0AMQBAAFMAaQBtAHAAbABlAEEAcgBtAAQAAAAQAAAAAQAAAAEAAAAYAAAAfalsefalsefalseyDIAAAUAAAD//v8VVAB1AHIAbgBUAGEAYgBsAGUALQAxAEAAUwBpAG0AcABsAGUAQQByAG0ABAAAABAAAAABAAAAAQAAABkAAAA=falsefalse -2020-12-21 21:27:31,234 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\ustuner\Desktop\wroboarm_21 -2020-12-21 21:27:31,236 INFO ExportHelper.cs: 147 - Beginning the export process -2020-12-21 21:27:31,238 INFO ExportHelper.cs: 153 - Creating package directories with name wroboarm_21 and save path C:\Users\ustuner\Desktop -2020-12-21 21:27:32,837 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at C:\Users\ustuner\Desktop\wroboarm_21\CMakeLists.txt -2020-12-21 21:27:32,845 INFO ExportHelper.cs: 166 - Creating joint names config at C:\Users\ustuner\Desktop\wroboarm_21\config\joint_names_wroboarm_21.yaml -2020-12-21 21:27:32,853 INFO ExportHelper.cs: 170 - Creating package.xml at C:\Users\ustuner\Desktop\wroboarm_21\package.xml -2020-12-21 21:27:32,854 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\ustuner\Desktop\wroboarm_21\package.xml -2020-12-21 21:27:32,867 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in C:\Users\ustuner\Desktop\wroboarm_21\launch\ -2020-12-21 21:27:32,876 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in C:\Users\ustuner\Desktop\wroboarm_21\launch\ -2020-12-21 21:27:32,883 INFO ExportHelper.cs: 187 - Saving existing STL preferences -2020-12-21 21:27:32,884 INFO ExportHelper.cs: 450 - Saving users preferences -2020-12-21 21:27:32,886 INFO ExportHelper.cs: 190 - Modifying STL preferences -2020-12-21 21:27:32,886 INFO ExportHelper.cs: 464 - Setting STL preferences -2020-12-21 21:27:32,891 INFO ExportHelper.cs: 196 - Found 0 hidden components -2020-12-21 21:27:32,892 INFO ExportHelper.cs: 197 - Hiding all components -2020-12-21 21:27:33,029 INFO ExportHelper.cs: 204 - Beginning individual files export -2020-12-21 21:27:33,036 INFO ExportHelper.cs: 270 - Exporting link: turntable -2020-12-21 21:27:33,038 INFO ExportHelper.cs: 272 - Link turntable has 1 children -2020-12-21 21:27:33,040 INFO ExportHelper.cs: 270 - Exporting link: gearbox -2020-12-21 21:27:33,041 INFO ExportHelper.cs: 272 - Link gearbox has 1 children -2020-12-21 21:27:33,044 INFO ExportHelper.cs: 270 - Exporting link: upperarm -2020-12-21 21:27:33,044 INFO ExportHelper.cs: 272 - Link upperarm has 1 children -2020-12-21 21:27:33,046 INFO ExportHelper.cs: 270 - Exporting link: elbow -2020-12-21 21:27:33,047 INFO ExportHelper.cs: 272 - Link elbow has 1 children -2020-12-21 21:27:33,049 INFO ExportHelper.cs: 270 - Exporting link: forearm -2020-12-21 21:27:33,050 INFO ExportHelper.cs: 272 - Link forearm has 1 children -2020-12-21 21:27:33,053 INFO ExportHelper.cs: 270 - Exporting link: wrist -2020-12-21 21:27:33,053 INFO ExportHelper.cs: 272 - Link wrist has 1 children -2020-12-21 21:27:33,062 INFO ExportHelper.cs: 270 - Exporting link: manipulator -2020-12-21 21:27:33,063 INFO ExportHelper.cs: 272 - Link manipulator has 0 children -2020-12-21 21:27:33,064 INFO ExportHelper.cs: 317 - manipulator: Exporting STL with coordinate frame Origin_link6_joint -2020-12-21 21:27:33,065 INFO ExportHelper.cs: 322 - manipulator: Reference geometry name -2020-12-21 21:27:33,151 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\manipulator.STL -2020-12-21 21:27:33,492 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:33,500 INFO ExportHelper.cs: 317 - wrist: Exporting STL with coordinate frame Origin_link5_joint -2020-12-21 21:27:33,501 INFO ExportHelper.cs: 322 - wrist: Reference geometry name -2020-12-21 21:27:33,526 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\wrist.STL -2020-12-21 21:27:33,599 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:33,610 INFO ExportHelper.cs: 317 - forearm: Exporting STL with coordinate frame Origin_link4_joint -2020-12-21 21:27:33,611 INFO ExportHelper.cs: 322 - forearm: Reference geometry name -2020-12-21 21:27:33,629 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\forearm.STL -2020-12-21 21:27:33,722 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:33,748 INFO ExportHelper.cs: 317 - elbow: Exporting STL with coordinate frame Origin_link3_joint -2020-12-21 21:27:33,748 INFO ExportHelper.cs: 322 - elbow: Reference geometry name -2020-12-21 21:27:33,766 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\elbow.STL -2020-12-21 21:27:33,831 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:33,841 INFO ExportHelper.cs: 317 - upperarm: Exporting STL with coordinate frame Origin_link2_joint2 -2020-12-21 21:27:33,842 INFO ExportHelper.cs: 322 - upperarm: Reference geometry name -2020-12-21 21:27:33,862 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\upperarm.STL -2020-12-21 21:27:33,946 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:33,954 INFO ExportHelper.cs: 317 - gearbox: Exporting STL with coordinate frame Origin_link1_joint2 -2020-12-21 21:27:33,954 INFO ExportHelper.cs: 322 - gearbox: Reference geometry name -2020-12-21 21:27:33,978 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\gearbox.STL -2020-12-21 21:27:34,045 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:34,052 INFO ExportHelper.cs: 317 - turntable: Exporting STL with coordinate frame Origin_global -2020-12-21 21:27:34,052 INFO ExportHelper.cs: 322 - turntable: Reference geometry name -2020-12-21 21:27:34,070 INFO ExportHelper.cs: 330 - Saving STL to C:\Users\ustuner\Desktop\wroboarm_21\meshes\turntable.STL -2020-12-21 21:27:34,126 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2020-12-21 21:27:34,132 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components -2020-12-21 21:27:34,218 INFO ExportHelper.cs: 145 - Resetting STL preferences -2020-12-21 21:27:34,219 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences -2020-12-21 21:27:34,220 INFO ExportHelper.cs: 228 - Writing URDF file to C:\Users\ustuner\Desktop\wroboarm_21\urdf\wroboarm_21.urdf -2020-12-21 21:27:34,314 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\ustuner\Desktop\wroboarm_21\urdf\wroboarm_21.csv -2020-12-21 21:27:34,356 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,357 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,357 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,358 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,358 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,359 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,360 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2020-12-21 21:27:34,368 INFO ExportHelper.cs: 234 - Copying log file -2020-12-21 21:27:34,373 INFO ExportHelper.cs: 439 - Copying C:\Users\ustuner\sw2urdf_logs\sw2urdf.log to C:\Users\ustuner\Desktop\wroboarm_21\export.log diff --git a/src/wroboarm_21/launch/chomp_planning_pipeline.launch.xml b/src/wroboarm_21/launch/chomp_planning_pipeline.launch.xml deleted file mode 100644 index ca38555e..00000000 --- a/src/wroboarm_21/launch/chomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/default_warehouse_db.launch b/src/wroboarm_21/launch/default_warehouse_db.launch deleted file mode 100644 index 1145f07a..00000000 --- a/src/wroboarm_21/launch/default_warehouse_db.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/demo.launch b/src/wroboarm_21/launch/demo.launch deleted file mode 100644 index 54b5b132..00000000 --- a/src/wroboarm_21/launch/demo.launch +++ /dev/null @@ -1,64 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - - - [move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/demo_gazebo.launch b/src/wroboarm_21/launch/demo_gazebo.launch deleted file mode 100644 index eb59236f..00000000 --- a/src/wroboarm_21/launch/demo_gazebo.launch +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - [/joint_states] - - - [move_group/fake_controller_joint_states] - [/joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/demo_test.launch b/src/wroboarm_21/launch/demo_test.launch deleted file mode 100644 index d722f59d..00000000 --- a/src/wroboarm_21/launch/demo_test.launch +++ /dev/null @@ -1,66 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - [control/arm_joint_states] - - - [control/arm_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/display.launch b/src/wroboarm_21/launch/display.launch deleted file mode 100644 index 5b8e9435..00000000 --- a/src/wroboarm_21/launch/display.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - \ No newline at end of file diff --git a/src/wroboarm_21/launch/fake_moveit_controller_manager.launch.xml b/src/wroboarm_21/launch/fake_moveit_controller_manager.launch.xml deleted file mode 100644 index f6c0f465..00000000 --- a/src/wroboarm_21/launch/fake_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/src/wroboarm_21/launch/gazebo.launch b/src/wroboarm_21/launch/gazebo.launch deleted file mode 100644 index 6e80529e..00000000 --- a/src/wroboarm_21/launch/gazebo.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/joystick_control.launch b/src/wroboarm_21/launch/joystick_control.launch deleted file mode 100644 index 9411f6e6..00000000 --- a/src/wroboarm_21/launch/joystick_control.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/move_group.launch b/src/wroboarm_21/launch/move_group.launch deleted file mode 100644 index 1910c99f..00000000 --- a/src/wroboarm_21/launch/move_group.launch +++ /dev/null @@ -1,82 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/moveit.rviz b/src/wroboarm_21/launch/moveit.rviz deleted file mode 100644 index 87a9b996..00000000 --- a/src/wroboarm_21/launch/moveit.rviz +++ /dev/null @@ -1,276 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 84 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /MotionPlanning1 - - /Pose1 - Splitter Ratio: 0.7425600290298462 - Tree Height: 357 - - Class: rviz/Help - Name: Help - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/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 - - Acceleration_Scaling_Factor: 1 - Class: moveit_rviz_plugin/MotionPlanning - Enabled: true - Move Group Namespace: "" - MoveIt_Allow_Approximate_IK: false - MoveIt_Allow_External_Program: false - MoveIt_Allow_Replanning: false - MoveIt_Allow_Sensor_Positioning: false - MoveIt_Planning_Attempts: 10 - MoveIt_Planning_Time: 0.5 - MoveIt_Use_Cartesian_Path: false - MoveIt_Use_Constraint_Aware_IK: true - MoveIt_Warehouse_Host: 127.0.0.1 - MoveIt_Warehouse_Port: 33829 - MoveIt_Workspace: - Center: - X: 0 - Y: 0 - Z: 0 - Size: - X: 2 - Y: 2 - Z: 2 - Name: MotionPlanning - Planned Path: - Color Enabled: false - Interrupt Display: false - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - dummy: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - elbow: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - forearm: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - gearbox: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - manipulator: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - turntable: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - upperarm: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Loop Animation: true - Robot Alpha: 0.5 - Robot Color: 150; 50; 150 - Show Robot Collision: false - Show Robot Visual: false - Show Trail: false - State Display Time: 0.05 s - Trail Step Size: 1 - Trajectory Topic: move_group/display_planned_path - Planning Metrics: - Payload: 1 - Show Joint Torques: false - Show Manipulability: false - Show Manipulability Index: false - Show Weight Limit: false - TextHeight: 0.07999999821186066 - Planning Request: - Colliding Link Color: 255; 0; 0 - Goal State Alpha: 1 - Goal State Color: 250; 128; 0 - Interactive Marker Size: 0 - Joint Violation Color: 255; 0; 255 - Planning Group: arm - Query Goal State: false - Query Start State: false - Show Workspace: false - Start State Alpha: 1 - Start State Color: 0; 255; 0 - Planning Scene Topic: move_group/monitored_planning_scene - Robot Description: robot_description - Scene Geometry: - Scene Alpha: 1 - Scene Color: 50; 230; 50 - Scene Display Time: 0.20000000298023224 - Show Scene Geometry: true - Voxel Coloring: Z-Axis - Voxel Rendering: Occupied Voxels - Scene Robot: - Attached Body Color: 150; 50; 150 - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - dummy: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - elbow: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - forearm: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - gearbox: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - manipulator: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - turntable: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - upperarm: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Robot Alpha: 1 - Show Robot Collision: false - Show Robot Visual: true - Value: true - Velocity_Scaling_Factor: 1 - - Alpha: 1 - Axes Length: 0.10000000149011612 - Axes Radius: 0.029999999329447746 - Class: rviz/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.07000000029802322 - Head Radius: 0.05000000074505806 - Name: Pose - Queue Size: 10 - Shaft Length: 0.10000000149011612 - Shaft Radius: 0.029999999329447746 - Shape: Axes - Topic: /logic/arm_teleop/next_target - Unreliable: false - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: turntable - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - Value: true - Views: - Current: - Class: rviz/XYOrbit - Distance: 1.7158159017562866 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Field of View: 0.7853981852531433 - Focal Point: - X: 0.05638057738542557 - Y: 0.06656442582607269 - Z: 1.6391335577736754e-07 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.6097966432571411 - Target Frame: turntable - Yaw: 5.253137111663818 - Saved: ~ -Window Geometry: - Displays: - collapsed: true - Height: 1016 - Help: - collapsed: false - Hide Left Dock: true - Hide Right Dock: false - MotionPlanning: - collapsed: true - MotionPlanning - Trajectory Slider: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000100000000000002a20000039efc0200000007fb000000100044006900730070006c006100790073000000003d000001c2000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a0056006900650077007300000003b0000000b0000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670000000205000001d60000017d00ffffff0000045e0000039e00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Views: - collapsed: false - Width: 1118 - X: 802 - Y: 27 diff --git a/src/wroboarm_21/launch/moveit_rviz.launch b/src/wroboarm_21/launch/moveit_rviz.launch deleted file mode 100644 index 615b2f12..00000000 --- a/src/wroboarm_21/launch/moveit_rviz.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/ompl_planning_pipeline.launch.xml b/src/wroboarm_21/launch/ompl_planning_pipeline.launch.xml deleted file mode 100644 index 8ae6467c..00000000 --- a/src/wroboarm_21/launch/ompl_planning_pipeline.launch.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/src/wroboarm_21/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml deleted file mode 100644 index 9478782e..00000000 --- a/src/wroboarm_21/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/planning_context.launch b/src/wroboarm_21/launch/planning_context.launch deleted file mode 100644 index d57c692d..00000000 --- a/src/wroboarm_21/launch/planning_context.launch +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/planning_pipeline.launch.xml b/src/wroboarm_21/launch/planning_pipeline.launch.xml deleted file mode 100644 index c64f6d61..00000000 --- a/src/wroboarm_21/launch/planning_pipeline.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/src/wroboarm_21/launch/ros_controllers.launch b/src/wroboarm_21/launch/ros_controllers.launch deleted file mode 100644 index f23ccb91..00000000 --- a/src/wroboarm_21/launch/ros_controllers.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/src/wroboarm_21/launch/run_benchmark_ompl.launch b/src/wroboarm_21/launch/run_benchmark_ompl.launch deleted file mode 100644 index f4cc195a..00000000 --- a/src/wroboarm_21/launch/run_benchmark_ompl.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/sensor_manager.launch.xml b/src/wroboarm_21/launch/sensor_manager.launch.xml deleted file mode 100644 index 31fd01af..00000000 --- a/src/wroboarm_21/launch/sensor_manager.launch.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/setup_assistant.launch b/src/wroboarm_21/launch/setup_assistant.launch deleted file mode 100644 index 05acb517..00000000 --- a/src/wroboarm_21/launch/setup_assistant.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/trajectory_execution.launch.xml b/src/wroboarm_21/launch/trajectory_execution.launch.xml deleted file mode 100644 index 26c4b149..00000000 --- a/src/wroboarm_21/launch/trajectory_execution.launch.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/warehouse.launch b/src/wroboarm_21/launch/warehouse.launch deleted file mode 100644 index a19014e8..00000000 --- a/src/wroboarm_21/launch/warehouse.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/warehouse_settings.launch.xml b/src/wroboarm_21/launch/warehouse_settings.launch.xml deleted file mode 100644 index e473b083..00000000 --- a/src/wroboarm_21/launch/warehouse_settings.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_21/launch/wroboarm_21_moveit_controller_manager.launch.xml b/src/wroboarm_21/launch/wroboarm_21_moveit_controller_manager.launch.xml deleted file mode 100644 index cd0d7e3d..00000000 --- a/src/wroboarm_21/launch/wroboarm_21_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/src/wroboarm_21/launch/wroboarm_21_moveit_sensor_manager.launch.xml b/src/wroboarm_21/launch/wroboarm_21_moveit_sensor_manager.launch.xml deleted file mode 100644 index 5d02698d..00000000 --- a/src/wroboarm_21/launch/wroboarm_21_moveit_sensor_manager.launch.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/src/wroboarm_21/meshes/elbow.STL b/src/wroboarm_21/meshes/elbow.STL deleted file mode 100644 index 5b1cbba57c6643476f46e02ded4e495662aa8126..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8084 zcmb`LUx-yz6vhuqqmh_3+8=WqYi>|bHsz!?bLJjRGZMo;A!I29GSGuqJ*b2tD%24E z=_PtnW?%-)Ae^mAXFSEF7{r0!l z+H3E#&xxY{_pjd$wD}NSwky|8Jg%35E!X(b>Tsj5^w#!s`g6njFGYi z#{$79YJ}HA^H2iz`ra8`VGXW1qc}rUy-b+7qy9EqQw6LVvbS9l&KzCB%$30UqeIIY zN-&C`#7B7rDsWPMd4eDBscE-PaGyItFmKu(AP;Va@gF-OpYD0Uxg%=Xr^Qi6RP zt`+lO6g1ciWr7|=DPi=+cWo{YB^U+TOLWT$9} z@VgdkZpQ@yJKMDr5{P0>*(sVMFn51`us%3f?0VdKR=#eQK&8Vw3hTi<7zGXPg7SLM zgD55Z`Um#85{&Y+-{-iGbgbxVF}IEMaNEPRQ>`ubY4FfL@6!POpubF5&H$UI8$e4LojDD8!O9$FLbTA%rCtcMajCBn1f3ThN8!r$|=QjZcm z$ATK!SQ>@3!E?7vsD~$~&paEc@vM~K8C=%TJTwZwH(c|~qXcX`al#rLOQW=>?dem& zodlYbw_P`Vb#{1@)lfog+q>?2Ns&M=`7e;!xX|P8QM7#O zlLwW7!8VWW_TsT;munmmdGJp}@F^Mu(^gJ#VWt~os*#6~Zm8m6y`1U&@; z>+cD(2M5g_OxU~hfDju!?Z2=T33>_y_J=2mw?2A6h;23aww=56Wu5|IX-AkHW%J-! zf^qpyF1D?eJFkiavgP}^5Vi`ASUY_0pg9v0o{36`%{7mss7Ux#i&-n`@%JeD_F8?w zob6Sf?eu^U+xD*e22do>iSQH%+q;g4r%oO)&!{S&QA&u-J!tYM5`Gt14I#L@3^8wT zXL|OrxPD;6tbX2D@#Lh9rzLO8?pdpZdP0PI*8X^OL;C#brnG(Oq<$r6BZ~KVr=f&; zLWI+JVa4q9+{#ty=p!S2O3+3WZgXy?dk06?R`qnMig(dPD2Ux zgb1gxIo4}18=9eUE)1m3EI>c|N2oR=m`@^dP0QL@LiHjT5!OwImaT6D0IyD*Fh!J6C#|3@Al-x^xnBj z&_)zGpI?p4+PNKN3H5{sr{Q;P^5FK_eM-6WB^--1 zqHq$8e~nT?Jt4wr_)|2w{^~#WOypRk5rq?#-?E}e3H5{sr{SLl)uk(D+OwTwkwz4s O3~mo9p`H-oH2wu$m;KNH diff --git a/src/wroboarm_21/meshes/forearm.STL b/src/wroboarm_21/meshes/forearm.STL deleted file mode 100644 index 63094c85c87ccbc3df1eeb137add10c22e680d53..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 14084 zcmb`NU5K4m6^3`Eibxx*tt8m0ZF6R{SlSTUi#mrnf>1)P3Y8$eP>ZP-dSgIn#b~EL zsV&5oP%j$%0h2S5l3J`JBALUS7SubTcNz@QN{|t}QBsVyrLK2>>)qeGf4(zb7zkO} z>wWgxf8W~cJLiP(|NXP;su2GC{cp~XT=??l?Z5u*=*8>r8;9`8>FMk5+wAOcV((|( z`Nd<8tc?Hp+?f@$=Y)D%1n3ZMTHZH*-;X{%|I<&Gmz1Cl)gLyl8XtK1)^Qg@3H7vy zE=E|sxcS%hugqWj+rA|wXhZe#UH7cqa$P(nQ|!efLNMj@=tk3RU>B_(Kkj17sA z6Uoye(mYnI%()dc72-M`#>QVH5n*@>Ci>4@hoo~uNtrzX~J$zrV9*_|rU*`3PijdXSqBNFOq z5nT+Q`NYodx)QXZ@>Q6nvy0V@gnC*;7sGdOVrO?<3EEKkZh8zQ)YBq7MtEUrXLn*} zcU=kE9%IGME@R|G^0bIF4?KgD*Oqr8h7!?+%0`IioH4qmHWKO~twa~YGsDEr?o?O=-+k$! z5ppihua9?zzVsy8ZXzef_MA{vL8nt$5y_(j=79fq^UzW0c~zC3u{?&3*G>s??FRbQ zcsZe-oIn;``$;`2B|O7LmACtT=seV;gvVQ{W2ndH6#Lbln)8S%C48T@8I`ImMmjN7 zjO0d80(UH=DxR4WvdV?B;Uc*)9|Qr0=a~lq1cbqSC>~hmCt-uk4imC zc)WPVnxl$+smkZ)F)TBr+Q;{H=J{%d|ErxcLn1t9L={IU*^ak?#313h1gntI-OP1V zEdnZQk0Wf3DtS06-@(}4jG;tQVRRfJa{Jl@BeR{fy5#kE-`)0+r;vBYmwxb#*(=A6 zMjOxkj;-%nO|a$R5|hU>5*%n+lC0CQ-QY8 zuC(WYjQsnzzZGX|%6OJQpvrjT_*x?dJy0nD8z-h-tCE0^aJuii` z>lYqAqlBu^j=RC9dk5vb#(qKYj74IO zdKCAed1ex0#(vQbDvc^5=z&U!5XSv!A0(*q7_)W^o;axFT*Y`PCuT9^>}CW{em!#~ zs6xCDKHul|ECxML<-{-h+&)Nz(5XOM?Ea1_h+bte;=Qz(U|&9}MA*8;JFz+Q7###v zux-`*yqk@Ro|0fjtz#%b6=>Wm={e70&;ykc%=2{&C8%PI^qf~Q;DJgB{6F1;g9KIh z7xPQcc}CC!l@hQAPdo4PNI(TOb~ZidSqyp@g9M+hdaZ0!F)um6%z*tE53W`8l!X0% zJh)aF;T1rPF}UZ<)G_0bU=FV5f$@5kfgOxD07i)Ur8_EHD|(<(f_F(BLkX%tGZV#1 ze~Qn1>{ggtbsu*Mm9SRD-J2diheOp$LOn{jJ??7iZHTDy*!~%^66(=@`EFRp(0RBj zzCq{+^O>th34b^A_YWPF5~{NHF;=)9m3ox$ch2pJ_?ZLx<(pR>!)89VCn~O@#~VY{ zz3FwI+~+e_j}kiCZHYK`kL{nT=~}5r`~BbM;i@U}L* zjfyKu6=+-aMrCQ9vFzYj_6E0ezvpwlL4u$Mwh|%S(0Cs#397ukpLrGoqe68Dl{~dE zUdo9Xfsy!akP*x)@mviOR3Tmn`x@_q>VcgTC;A&Fi^0A+x>Lc%ezfPI`=Kk%=f9o@ zJ?K{n*md0wRY^d__PTCY4`YyECTfogeSx3~Hg~or=qU+i)WrlJm{a|(29*+2q1|?{@mYp?U@I~FM6oXrRKd0a{a2&++V4v~YQHnlzEp*F zTZNb_Yl0pnV6#1h$IhM`U9#W%e87JFqJ60f?RHAyTX;>-qXcZW+zhhvpco5n%LRpJQ6_~F>G}`iqJ*q+s>`hmf*xAhpdX#|8_7JZ8=SF0>Rpvx`RD~GKl_7lU^k_*5dX#|8 zj2gn$b*H9F=MPT~?75lucC2yA?^sxI3=`;=DvXMD2z%Eyrtj=JIC=cgR*XT960liu zEGDQz4B8>Q@%(K1=GAvk{&Dr)@%f-f`-RFsghWPCRt($&d}5Z zUZcJ$38|bgk4Amv^I#R0REWWvCU{_sbFPA$GX zP0$OGmVQL5==J$GpNP1he(r(G(*!LfAa72#YDX{RZizWrws}nMU8bIgT*hj5a;&O_ zL>l#t2#xyCs!Grc{kvj5NWAps=Ec&gF-M(Sda)MTR&h))=UcR@n?YJgAjh`NL4saM z?-A*8(CeQczv14hRVN5qNTf)fkFixX7QHZ=9YG5!X2aY=&ub16sVbw!QssA*$XN7( zeykGbIFNumuG%%?5-kiO_QP2{QuYtM_0sNhKR=88>ifTWWq0TGN4R&z4CWow#NR&i z&E41k^%`gGphzG6#CLbMe)Q`Y-IlP0y_M|!SdrUSk+7GD=O6w-`Sj0CGhqo6rJYY!t)`f-pK z361p4pT5=3AbTE!y^v$29~>(Zs)g_U?mcfq*h@KFJ+&XRBw4tMzVXJ7YmIr-D?N8jD!P#VnUA>1#C({}`inSu?5*D>vW0Dz z>{jR7FrA`D{P?AQkf>f+e{UypjmQ?pmF!W-v7JX2>?PV2svQ2A&#^DXh!(nhrN*8Z^U)L8 zg0=_keI>l-%s9tF*em5073aF+>vs^SxbM;QK@0 z>dL#-_vbW`prt32BNJbH-(yiFm*4upISG8d>~+)6{nHmc30it0kAjGwedkM&Ga?^c(pGF-xMQCrXY)lzz;qA9qg>8}zRu zXhDu3%2*|$jP9J~<46KM-(a57?Ue*AJ)sZ<1;=bdX zzG#0ZjD%y!%eTJkw~B;s&SQ=;Q+oN28>{Z6$PqW0Wku1_6TUe&IpS{`0J(SkWgCH5_-!(j@7yf zBId(!MffZ1WR4*0CBo~bA!0r}Ch}5^=_M_al2GN3Z+(m<*vIaE= z4dHpZny{B>SN=$#+IJow5oNE;bKZ?r9o>fTNRK%jOL6Tb`Sj?@OE2{Da=oHed3~(4 zO4Z&FuKbg&3c_B<@isjt;q`bjN6etTl*83iiCK~?-jQ=l>RA%6we=-cJ+B0IQP)!R z$pRNn zR?#cvsHJ}X3qyLX$He9Rrw_&oo*G0G#^3xEkjhy zN32>`BE67ftSk3i|DU18g*?{P8qvLFAmk}dh25>dP(ndcO+~f zA=&y&r1cRu4aTCE_5Rz0sFv{G=pEPeLZ}}fOYbF&MK9^qbN%0jr5`42AtBlNOqBUJ zG8Vn0*9`irXqrgaLPE0jIY+6h$YBe;ltY#1ztK+<30p`=wm#=5)gC!)p_g*-W;snH zY#|}p`kLcRZ+(nKFX?@U9|>DXNVYx`|4#3He@<_Gj72Z$eTN?jTS!Q@J`>NT_r864 z>tif>NzXgnG?B1{gkV21l}^jiPR zd0uvg7+qT!SF-iFA3g^ei(b-eA6xDvBy1re+4`Krry66?OM0JOBVh{($<}AW=OAOz zOZw(ii@z}G9HfPWgY)wreV3W9_*Y|mr#vaB3HiAL-kUJ^@=sjMpjv)OOS>UlojTH_0g}Z7Z>S9z=T9iEJ}XYMr+r7BCmU5eQj|6>!~d?P#r$VgozN&^YSg-y$-rJl&Z!Ahz^6SVQWkU6wI(RLP()t{NJvwKbN7gQT z#TrcLj@hD)GHTu~;Ympy6)2rYo@^(p>?w(1HTZbmpGPKe<}6C;!}tEovxf=Qi#x{6 zDz3#*T3<_yaj)ZE)b7T+&pMrMyJ7w9#?b@mrp66TM9c~v-R+S!jV{3+%PMK4%DaU1 z1fG%@R*R2cZjlvwWl_44J`Kt`+6qM@o^9=n(8-B7`bF zIp+`$I>xv%U0Q{_K>mo<-UI?N8`DSxzY5(%EW8X*R*&bGp`j_Kf%bhL> z_JE!x(vx%B?kml;tKXNuEbVx~gxQGV*@VCZdpsg({Mvq`kX-DkpVM3wVrf;}FQG-MW2naRqTr}z3yn4O~99TNf*GdlzKhd#sk z>5O?p3qYnhEG=>p!)b?;(_7{MNoNE( zB-rB-Nkb>t$T=S|VK$<4npH9LNU+Bvl7{ZYM$Y+|39}KUyHYinV2?*64Lwnfobxdg zW~V5A%V1*WJprdn-*Maj4fD;=$T^qyQC_Q!61@TF)GO=|nR_HkPnXEO!kyU2IY%9N zEwd3NU5NivCk^RUCfMTzub5zuM_I4-sj!hH7N`PhMoEBcjw3M-3x zTG@Vexfi2kUHg&GJb6fn-cp>fn+Nw|l;o%V&zy=LpBSqZcPeX;kbYFs^L#&29*lC0 z{9L6OCE@mdwz|`VMfnLcglBHk?zJ-eY^Nge;cop-PGoepR+b^7MB_mJvw0*B3DMK3 z%xffqQ9jdMVkB=#>ly0AHJGc$Pi5;Vk04Z|N4Q?4JCzAW`KdAlJ-Df7JQWF<5`BGi z68~{3MtSDik33->5^n2UolaPkpD;s6ee^zSry5M9X1=T^>udN_TZT?pMV+ud_4=WE znTLdHXZpdt7{!U{YA{3ZrsbqL=zl*CdPw-h7~Rz%!6;cT)QTPw*Ehb!t?hR(?Zqgs zLgrLnQS*3jtk2Z$<&iW<$Xw|wnwb*r#VB7trROBvw&}^9%JyOu=S_*t+PMMLJKrp@ zZq>~aoN&_757n998OdHcKYFT&3Om-zL}&z|Rk!>sj~038UI(rb`>I~7kMqb8sxeI@ z4cC!xWvV=-5qhyc$)lCbNrXlaIMt7%g~Laep0&s4wucLM>h%2scH^^KX?}wN33>{I zoa*G{nH8%<@blbuYJBk0(OJR7Y!2h6bRAK&)AqN60k!<@409=v8k3vnWsQZ@>r2Pb~A*% zAAUmD@H~v52Xs`|=v3WW`Y|E_J9@4!pXA~FFv5Fao&q6x_>|N#S0fUzV|HDGgwK+B z3WR9*wAXS!MkHW2zvkY&l^k4y1U&^}tg#|@&@@QE);#bXPBaohPk|WMYDMm#)rtgc z?T7vzoYX22^b`oukPg;z2cv^&FVH$Avj6y(WtX6*K!}D+Vl8(tCNb>=TJHybL6V@S zK!^rEqe#FGjiq!4)2Et8nWsQZ^02ogLns}!at+VJ2tPYDrin>E>`f#AJ9=KFJE$Er w!h2wz0wEf5qjXB_Z6^UcX4f@H_$-;HK!}D zf}*>=RacN1Mi4DU-OR#;h~URU!M*XGI8Wpo8JV{bEa>jjan5tz_|C|Tnx_Bn&!Z33 ze7}D8+41g$H_q=oxj%jF7-n#wGNADm1dieS2GC`CwU{~UguROkf>4Vop z1CKP^{`RZCI{x!BZ>7c_L6kJGtH#S8yng-rS00B39%;CJ^@-mcU;EOhQe%%GN*dTz zJ50eep6ulrmv=M2rI-&ue;z%S6`dAPwwFWXrGJ<9TIg zzoo_=L6kCKSB)IO(7@w)W#{;(#vVbGG_b2i&fU0f+%TVhsONxZ@qc< zw=aJq=2i9F9G1K{(Yv=_dGGkSFTPYYIs%UqvMH|`|M~FC=YN$yQpe*_D*x!u-q)OX zIudxCkWG0d{!!ZSr_vVB*vcAuq zFuf$QuVT!dz?Me#;i+mkfyeX8ro0k4=AnVdqok2@AvK)9RL+_oHSj3P37*uAm}Pk` z*+j`^A8Uk+An>e-(zERZ(AqJ3F4;uM&f3OI?0c7yQdEvX^e!Vi)(X!yakKPppo(&$ z+Bc!`teliM_4T#Fv(T0JQJGWhSB;34J3*A_zn2pqr@lr+@8VIE6Q3{p;r85Rj*7^B z)0)3xPLF+sXHC5GWe_mV|p7Q5uChmicFy*VodJ(DocMEjPb=>@8-3*jQKEnFM7zTL{jpYf z6y?MZ%QK}!KR^&AdVkg8QIr#@C!N)pJ3*9ac8o^MvgFAfE_&2X1FVmYzVf;21W)az zA;Z?keP|FR?Oaj4#w?HTKCY2_@IuUJ;1N9%_X{B)G@S5WV7^5lXNDl~toto@@LnTY z?gUYynU%FN`ddH6(@uA?vxXc5iSE62pRhIG zy+`$gt?iaqdaVDkR!$Hlg0sX(;PJe&yS;?I(g?O(9wj@q>!}YSde>$~*V8;j$6Doh z#Hi&A4?BDMG!l4J6DM+<9w3Mkonx~>;8Bzl`z?2ZDA74K8ya{N<;3QAMDH@IMcDJa zt%9+yY-i{Q&JT^4Wht){M5&xzVkGb=%8C6kcY-L<>~^CD9z{99YHoy#XonL-iOv~w z7zsQ}RP4cw{|4bTu`^@tM7fLZu8)z3v*NP*%&Lj6sNCW7WVmI29NU3sq3d@hcGr#w z4JU{ay}$3`QIr#$44TF)%c5d!^L$k~&)`PL2m+7QBxs)0jhMFxqC|807zsRza)R?i zBVOy3Iw$J7MBQ)@+CT{yInWjC0C~06< zjq-*5T<$+Y1CKP^W>#J%h>`|&CCdHBx!ivo-6IX6WV2Q-6GSN!b`W!F+_}f|%1*r) z^J&^6h*Bo(s*!zlc8}+ko&A;?djwI+gk3dq1VaOl=arq~pBj4vQPRM!8aa1E1CQsG z%~}b9***|NNdvnQ_3v2(XG48|;g%%qH$V2B`2O1yCF)@N)fKkN_X#|z3B*vVxhR!C zv%ZVATppzwlBv}SqIsMscHdVeT0f!TM2iwZ4Qp)PE=BL+@m`S4IruU`lxm1wi84## zF4aArS2m~G%LGx%gk6ce?TdEc@w~D*2VW+Lk_L7qxJz}9=apUlv@fZ#&g1rVO%SDW z>`o*0D?H`jmREMx>TsDL%CwWnzPfgg=arp(_y9qaGGW(R<(P*C9?vT~XGv=85kyG? zyJ~PV>K@N4JLhz2>=8sM6L!_8f6vhlJf2r}uG-XqC?0m4csd)++T0+>RcgXY?VjzC zeRd5eI00O&RjaQwAk=c~LBoj_HS|@xMP58{*PLTeZ)Nz#Q8l=!7J+B!-AYqliM$z& zb&f{_wld{AZk&*(*$F&O$fmq%l$*G?clKN!rEic6%InOp_c+t!1Rf`3Q(iT=MfO}C zrE=aAMgor$vMFyZk6UEV{m{h&3K$@t+KCThsz#~FB3*E9!cbw z4}{Uog$*KSMrasuOL?tT+2M}m_pd?&k6LbayB{72{{~=0_nl$lH#tJX3A4K!te)^M zUPg4^$l{3;zbB)yb;9iKCax#^`;`&hH?l^=e&vMOXm9LSnO8eb%PX7mHcQ%mg~y}R zzU+m%YU$mxdsYPFkwlL9K#*6Nax^yxJkl_N856{EUt4yv_Pcem>&fEn7iE_}<^ALB z_`Ri`z_TX&9j7PotO?E!>fL>UDAD-_a2g3bigLnF8NG%RM2Yry&Yr-dC@1REAnt`% z?ZC55)RRopm=)zjK4pgQ42_r;;wGZ<3HJcO*8$N^_$i~;aDph&yfcjBfk#nJ)U(8D zUPa6C81eLf)(C> zy+l?F#v9-PmnzcDQU2er^FTe9Y@%dmZR6bD&s{ugBK7)N664_nQKDHZs*HYOmy3C2 XD-Qa|&Xa diff --git a/src/wroboarm_21/meshes/wrist.STL b/src/wroboarm_21/meshes/wrist.STL deleted file mode 100644 index 76da8c3574e5acb60d4e9171c059b2cc0e1944dc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 21884 zcmb_kf7E7GRX(t=Kn)sZC|zhVGv8}bfGCAH-<|g&EiJHg8Ye{=SHvpB1{j0kcMTL; zG%g1bmKj1znC}%yDSkMAG~fN+D_F+Da-pqQh6S`-Ab*HfET$X@+RwiGIrH2f?|l3b zYklip-m{;x_t|@&{hV{&^G-_tzyE#lpp;g;^Ro3@ue-Xu_DvVA{oLfiJ->4OJ1Tpw zJLs{mueo#Oh6)w@vmS9{O> z?mXUK*mqd9r9Qf_zxQss1$V23n~55&R;KfUA?)y;bjNA4z?&_>+jsZ zc-;7u%APjz`I}db-g?mo%g?O-M$5Y@rG884_UA4ieP!qF@tfbj)pdlVk2btoglFO5 zBBdL*eWkentDhdPdhp^}Tf#a-(b4QFr5ldDbYvEd&9asbMZ_2|7Sr+W51lu<=lm7r zk$=6hg-|JtW=ijQ$8E*>T|ZK8yz9M=V4M{Z9!E?}$JKM^j4XPkMX`lYDb0nHHe9l$ z*!0hPm$n_f-4Vz(_=Fj0PakZu zt#9pJf83fz2N5cTkux?az3q})Nd($XX}Z@b-%l!{?E@hS%O)Lxy_k{IKx+%8%n$p!V@m1H>hNO6EoJ?{mvZ$fP<@z@uo70$+LZq0 z`ol)g9`cJd{OOlzx!bAa`rYU2jn-9aBnA{OwcoU;F$y_1)iVst+QDy31J# zPe3<(25VFL`=9vi9Q*`-X^SGF5(VPPH$OH9i=-xci%RL3zz!Q0Qo5%8g}2S$3LVH# z@I`P2-q*?J>r#5>9gp0O3_+%7iy}A!kc}x_@JCDYH|@NRm&;`}lexygL>tw~Db5FPK%q&b6`gSX*>V?Qs}8 zPmG;wW9Jf5k#UQ7k2z6E9#@&2Yh&k9TO^k%?aA4B5}DZ2p$N%J8;7y;#MrqucJ_GC zDwTqc$Pz;YJJ-g}u7fR#keD07*m)9J;yQ>>skX0-ohQc5Q)6e>VUnmmK3elO>SHDK z(R>x`JT-PMwZ(M#Itx#XgFQJrPol!LbSOfqo#`-ko)|mV#?CE-N@+ARJJ-g}j$oV> zA@$017&}j*!nF`8rMZyVdA+f-BO)8QlJvDHtTIN8wdoztUNqqfR$GE)9MQ073dG)n zubLP;FBv<#4)&!|=!vn(?7U>`OshO^wGhc0}Y8SCYQ2 z4yzV{batLtbsJliqYiJ0m^&hL1j5)ER$1 zPO$EQzbJL*%7?LH@=V7&da@_}iZ()96u}%jFhZp`SNaH68MK7H0`E=j!XBqZf2 zdDz#XEv7Fc%)$b>)kj!f&0AJO(pTc9&));>?`^BJB`kEQ(7g;orNS!rbX$kESTqaN z6j-Rb+X!t@gk_J-i)(J{k6aNd6`xl#5#FMR&^O>+?MtO*$3tTtv2lIc)8NQmN)cA= ze7$hsaj2B(Krh}?Pe*Q11S{&G4n@RD>0#`7eC^Oj=sXCi0#ad>zYkjFEs6-MmO-dg zcy}1#pTZJF*gL$tJR(a)YyyFrj@_5l_z|>|SMg2`534HEZ7YBSAs~T2Ajlzo1ZEMk zFr@sHB6Q5K3Zuqf7h%@MIYZYfMNkT8)D`4*-zps~`8BMXF>;I)e~?lHSC@SqilCI} zunN%~hf2jecEa!mbPpid0x3m=g##m31f_ruj|?C*g0KRAK&12;<62a@?l{;Iwr2!& zFN^Te0v#)x0UeAjq--3R<2WgDU9hmPLv2@t`3*=EUGFkdkct`X@tEyhwsa9OYlnT6V?ZgOXU8Kviv0lRoxgK@{c*6Ri-;M# zjCUyov{~rq4}BeM3ENSL+|$(EN3f-fuqYUxH{Tu2jv%Fgww~a_;c<8iq!ba}T?RoZ zpd&VhKuyQ~#`>#eh143Ytb;lTZ3)}mepwTB5Y|#bJ4R?|-&)F-GRHV555+EW{$EsAJr2)v?{kK!g7o|$WC5qUn*r*d4=oi&=wnq^Ae=Ar}j9sMG@w=qN%|H@yO#) zsp!eu26Y5#f4`w`U`A?kbX+62``r}|r7hx7UHy#*4DWLcBc{d(myYp*|oLmb}TO_-P7Gt-R7K z2}?XnVtm8i^=OIhj)*ZWgP@f7t=WIHtcn<5b&t$PZ2bMDS)~ZDGZ|Jk#lp^B2S?RaN!M+6HXUNRAzE#WyAR;!5x$EvDREHvBZZ0zpO2xFco3<#A9-MqbQBc!nz?-iPxFIuwB& zJ;&tPzCpifaB28mEWtZJcdG^wu0zKZ?+v1Lp8@@c4)n`+e*%S(w{Jj%6m%$p?}pHO zGV}+YWHmg2j`$mbH<0X>-Y%}&@a)_o@Utwe(%h<+udIKc&*(SaaYw_~*A3#8Z#;BY z-0Q>l9|h+cS2dAW8SOU*s<_wZ2==Q8=CD1jigv#F$$hC*+p0rX|6n0*0^&O_p1mN$ zxuXYfc= zRon#hanQSp;2cLS>wO=Uu3@(Oni^1I(PsNyCd z?i%D4Rs~oIG<)iOUz=ML!4)TTr*y*R<8jvjHvwB#sT6bs!x_SE0#m~Xjc8h6&K>J z0d4}e5Gtjy@w*09+ytam9yLXTKJ3>_N9SAp96^=R$ogG_DsBS04(3xt5Z^X2WBd## zrMZ8(5_b)76OdMUiy}ftAnbmk-hhBr-l9_KH@|C8#Z5rh!MPU^^zYds6XX2q$G&|5 z?i%1GU~3$Th>Qt@-D1^yGRR$TQ7Ijh-!-V>CZOwJK81CjXOX)&Z?||xCzKg?W`Z;@i_^rXl+WnUvbmFQ-dwsZdpQR{`r}pGr zt2a!u4n;_gSv-tu=i*+UN03&j6m)RrX0FA(J|72L6d_q+Iy$#Mb6+Z@x!_!jTlcuv z=Q`*~sc=4W_K>+2_xf<_o;5M+f|VG@enjWya&F;x@RZtR@i4B%t$W<-bF0{wN@+AR z*WzBEBNzuo(BpXaZZ7ATtCZ$KW;NWPt2zJhgeCM_FdV)&Fdf&O`*XNMk6U`RwkQJc z{PxVo@s}UNJ$?L^rH7zY==PJ&yaK>&Lt5o6+HdGvM7-L!?zJzKipU1Sm=kyCaZ8Ue z_ZCG&H1Vyw>9BkHU}xL}thGfEc(=%6ZD$DmZAKSCsfcDEj5%?K9=G&rZP9)snz+Yg zI_#c4*cmqgYi&^k-Yt84HQxShMi)V;$dW)9bK(v?Zt1a>c#HNM*;(P4*%>zhYi&^k z-c5gnx!?ZHPZvR{s1kuN<{ZT>J$_f@E!uC)vI@`4&bSFU)fPqI-D2hEGwt8}bP<$_ z>JtcK&bheVMvn3p?Kfstg=c1G+@QlvKwpjFsR+DVURPj<-rd0#f>OaHfxx+|t&08b zptfkg^0{#o*VA?*p8HzwOQrOeXem8?(?=FC$1&GK3f#Bn?Z5XpZunYOwC>ZJ4*X6H zD}WzAHE)zx}!=7ql_J4-c>2~ zWKXjSj0xua?T?&0AJm3IktV{ z?3Rupgdt4_7!%BS*HdS-5bPIHj8o&Q9dCJG{h9|}R^Pns)Eq&yC?YDK?_N^kFKbR* zdD=w#QYn6pTuAA%W46~PJ-T=OubuD==AUO9bO`&{Nfff4-;!}|Z2rkhC)zTMz%CUW z3$DFvx~+xSkKWLVjop~ves%p*|8(Wj_LpzT@qkr|2z{74rXzllGX1w}E}CeZRf?ZC zF@NZ+t@Yg>+dcl_rYEpR^K65Th#=UKR>gOB+(~@=>@C#cEklS#M_4uf^ZiyiA}j$@ zw>+KFVSlx;-nV5%`P9CL<|9%z>W8a{AlQ=e539KAdi;kQnOEL2gg}nv+#Nsq^_;to zpcf#eV@m1E_a9q-;nuReZuhgF zFF;DiWHJB#Gt)o&!a3#5w|<&CEJp~#5UyB$! zw{)QYE&@nr=P}NZjh*MTFTUf+aWuX%b}o&b%V6gmHAPs=vC79<)O7HdHO9_!+Luc4 zb3C1$OPnDaJCE28w4)Zn+xp&AQDf)Q*m)f6oTG)DV&B@6S2+Kbg|Tx>#}EQYXXg@U z$i~hs1pCF4UT%D4>|7cvI;=aKfMQv4iGXXnz`c`4W#BcF$M zWT9oFXM8hf{FfGnh}pDs#3!yDX-gmBcMS}IvtyhgKk~(mEkuKEq%=0p&ZV*Q`e5fA zHARFzpD)hN_=V8e*mLa{*|{`!u7jNs^8!{y1br12@eixGvom&PUU|z90?3@ZQ)A~A zg8kyDV{&#bjh*XYXH*}zDk?)E6~aGvcJ^Jcu`@GqCZfs2_*GbK?A$^`z7}}un4F!* z#?E!HGir(Jh|1vWt(Y5O6;BL|omsDDB7n>_u{L&QO>_kN#Z$eIxwbYoSio$u7#FBI zF`Im+$M$k7k!gqV>Z_yi$$|tFmLSK-ye4-A2Z*&Al)wTj4NBKAu0V`>(uK>oj z0;ppJko!`psEy%Wo)Xy#fR)-?h7e7qj@n+^3ZR8xzj$gieeX;@Uy6}?o$7GAR|T~D z3V^$9An2cUo!$1j@S7pS(gWcH7`{?6&iI6FP(kEk0NS^Ouuc9UtB1^8p0!4hEkueXh;t(QhNAvB`Xn z-FA)#tP(z_KA(q~&!-*cY)Mf^6Z7D6?6&jj5jrA*K63-Hh|e>hk6+x+=iV}eXms!w zznxVEv(KxidOGttcH4^)sS4U7g3hE7|FA0fyu9uC%;(-Rgg}nv+#Pq;qRcBlG1oC= zKF4kw`&aHJSQ#qR616t-d0GBO=5rrMa9<12WMbrQ*;$L`ej%k}%6yL9w(c5O8GN>? zwZ7Z--|4^iRhiG-s;D?E1Zr2ViDhSx!^-LB;yR|xgV+hPw!4m~=U#!LCi>?o1rL_b z-kW)FCZefuGxj)S98^~R8#z9vd?H*LN9m3p2w%A($N1jph!bJ#IpJNG!qdiq+UVl| zV`7z_v0IQiE0?6LpIrqhW@w7kiW9aCdx96521U~ci)fn?ociXU+{X$A(lTWrw z<653NyLMzCVhuFko7|0)ZS0*$!HmjM)PZL{*&Z9$PEcJilb{3j4_?*x zrY6S8Hulb_?Jk9L^KsHPPR+q+Ll%97f;5i@l~8`WAB_J zh!#ay^?~oa2IrIQvU56!8kMD}qsfvu*~Z@4D?jE1bXayH8OlG4bg6eru*J3G4| zpP(aRj@m-2{B!48|Cg+cYk9Ig6Vc>VSk*mm&;3G5J)KXsv3Ca7`rLz65kbsW#y_lz zlkM8LmU-nZLx?65XM8J@`-PNxA)jnx@65Aei^apN46P?V&nMfpaV<}_XCj(RjFauU z^Q{c$gg - - wroboarm_21 - 0.3.0 - - An automatically generated package with all the configuration and launch files for using the wroboarm_21 with the MoveIt Motion Planning Framework - - me - me - - BSD - - http://moveit.ros.org/ - https://github.com/ros-planning/moveit/issues - https://github.com/ros-planning/moveit - - catkin - - moveit_ros_move_group - moveit_fake_controller_manager - moveit_kinematics - moveit_planners_ompl - moveit_ros_visualization - moveit_setup_assistant - joint_state_publisher - joint_state_publisher_gui - robot_state_publisher - tf2_ros - xacro - - - - - - diff --git a/src/wroboarm_21/urdf/wroboarm_21.csv b/src/wroboarm_21/urdf/wroboarm_21.csv deleted file mode 100644 index a9b9bbac..00000000 --- a/src/wroboarm_21/urdf/wroboarm_21.csv +++ /dev/null @@ -1,8 +0,0 @@ -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 -turntable,-2.82541936962439E-17,6.93889390390723E-18,-4.24870678161208E-34,0,0,0,0.396806230030924,0.000571454150237484,-2.23834839552239E-21,1.37054783361242E-37,0.000571454150237484,3.23777898172651E-20,0.00110024104924718,0,0,0,0,0,0,package://wroboarm_21/meshes/turntable.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/turntable.stl,,TurnTable-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, -gearbox,-5.70181409604587E-18,0.0380153243966357,-0.00138922050969218,0,0,0,0.341209853046385,0.000637264883384741,6.24923664103596E-20,-2.71681384497167E-19,0.000834504397618049,1.62941368108056E-05,0.000889318878925749,0,0,0,0,0,0,package://wroboarm_21/meshes/gearbox.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/gearbox.stl,,Shoulder-1,Origin_link1_joint2,Axis_link1_joint2,link1_joint,continuous,0,0,0.0127,1.5708,0,0,turntable,0,1,0,,,,,,,,,,,, -upperarm,1.49614561175028E-17,0.157206632847804,2.77555756156289E-17,0,0,0,1.26412421587631,0.0136779903910557,3.22448390771324E-19,3.96119838307109E-20,0.000964387075304149,-2.67429553724681E-18,0.0140917496737089,0,0,0,0,0,0,package://wroboarm_21/meshes/upperarm.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/upperarm.stl,,UpperArm-1,Origin_link2_joint2,Axis_link2_joint2,link2_joint,continuous,0,0.07239,0.03683,0,0,0,gearbox,1,0,0,,,,,,,,,,,, -elbow,7.33210423758527E-18,0.0462797200039115,-0.00991708285798099,0,0,0,0.625328404239412,0.00150936287881219,7.22519589370286E-20,2.65311197270661E-20,0.000771504125821615,-1.13468871077225E-05,0.00102329905512323,0,0,0,0,0,0,package://wroboarm_21/meshes/elbow.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/elbow.stl,,Elbow-1,Origin_link3_joint,Axis_link3_joint,link3_joint,continuous,0,0.381,0,-1.5708,0,0,upperarm,1,0,0,,,,,,,,,,,, -forearm,-1.32860243738577E-17,-1.90819582357449E-17,-0.113066392198771,0,0,0,0.460632401231927,0.00223620566444836,2.86239968572403E-21,-5.06454254732662E-20,0.00224684031586386,-3.05817065058502E-19,0.000245602268076572,0,0,0,0,0,0,package://wroboarm_21/meshes/forearm.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/forearm.stl,,Forearm-1,Origin_link4_joint,Axis_link4_joint,link4_joint,continuous,0,0.04445,0.04445,3.1416,0,0,elbow,0,0,1,,,,,,,,,,,, -wrist,-7.1276563552947E-09,7.80625564189563E-18,-3.41498918032812E-09,0,0,0,0.0642008901362293,3.49809093099438E-05,5.28878027298075E-11,1.56594471999825E-18,2.42909279281571E-05,-4.37083043679572E-11,2.86709715099874E-05,0,0,0,0,0,0,package://wroboarm_21/meshes/wrist.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/wrist.stl,,Wrist-1,Origin_link5_joint,Axis_link5_joint,link5_joint,continuous,0,0,-0.254,3.1416,0,0,forearm,1,0,0,,,,,,,,,,,, -manipulator,5.8113236445223E-17,1.74020910368395E-17,-0.05715,0,0,0,0.237050487139156,0.000319176967769642,-3.08271195529153E-21,3.16873566981017E-20,0.000319176967769642,7.05373762522642E-20,0.000122196649085178,0,0,0,0,0,0,package://wroboarm_21/meshes/manipulator.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_21/meshes/manipulator.stl,,Manipulator-1,Origin_link6_joint,Axis_link6_joint,link6_joint,continuous,0,0,0.0254,3.1416,0,1.5708,wrist,0,0,1,,,,,,,,,,,, diff --git a/src/wroboarm_21/urdf/wroboarm_21.urdf b/src/wroboarm_21/urdf/wroboarm_21.urdf deleted file mode 100644 index d5cdc0f7..00000000 --- a/src/wroboarm_21/urdf/wroboarm_21.urdf +++ /dev/null @@ -1,306 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/DifferentialTransmission - - actuator1 - hardware_interface/EffortJointInterface - 1 - - - actuator2 - hardware_interface/EffortJointInterface - 1 - - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - - - - - - / - - - \ No newline at end of file diff --git a/src/wroboarm_22/.setup_assistant b/src/wroboarm_22/.setup_assistant deleted file mode 100644 index 85e8ffb2..00000000 --- a/src/wroboarm_22/.setup_assistant +++ /dev/null @@ -1,11 +0,0 @@ -moveit_setup_assistant_config: - URDF: - package: wroboarm_22 - relative_path: urdf/wroboarm_22.urdf - xacro_args: "" - SRDF: - relative_path: config/wroboarm_22.srdf - CONFIG: - author_name: Nicholas Underwood - author_email: ndunderwood@wisc.edu - generated_timestamp: 1643850775 \ No newline at end of file diff --git a/src/wroboarm_22/CMakeLists.txt b/src/wroboarm_22/CMakeLists.txt deleted file mode 100644 index 0d3118b1..00000000 --- a/src/wroboarm_22/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) - -project(wroboarm_22) - -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/src/wroboarm_22/config/arm_assembly.srdf b/src/wroboarm_22/config/arm_assembly.srdf deleted file mode 100644 index f9dfd6b0..00000000 --- a/src/wroboarm_22/config/arm_assembly.srdf +++ /dev/null @@ -1,43 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/config/cartesian_limits.yaml b/src/wroboarm_22/config/cartesian_limits.yaml deleted file mode 100644 index 7df72f69..00000000 --- a/src/wroboarm_22/config/cartesian_limits.yaml +++ /dev/null @@ -1,5 +0,0 @@ -cartesian_limits: - max_trans_vel: 1 - max_trans_acc: 2.25 - max_trans_dec: -5 - max_rot_vel: 1.57 diff --git a/src/wroboarm_22/config/chomp_planning.yaml b/src/wroboarm_22/config/chomp_planning.yaml deleted file mode 100644 index 75258e53..00000000 --- a/src/wroboarm_22/config/chomp_planning.yaml +++ /dev/null @@ -1,18 +0,0 @@ -planning_time_limit: 10.0 -max_iterations: 200 -max_iterations_after_collision_free: 5 -smoothness_cost_weight: 0.1 -obstacle_cost_weight: 1.0 -learning_rate: 0.01 -smoothness_cost_velocity: 0.0 -smoothness_cost_acceleration: 1.0 -smoothness_cost_jerk: 0.0 -ridge_factor: 0.01 -use_pseudo_inverse: false -pseudo_inverse_ridge_factor: 1e-4 -joint_update_limit: 0.1 -collision_clearence: 0.2 -collision_threshold: 0.07 -use_stochastic_descent: true -enable_failure_recovery: true -max_recovery_attempts: 5 \ No newline at end of file diff --git a/src/wroboarm_22/config/fake_controllers.yaml b/src/wroboarm_22/config/fake_controllers.yaml deleted file mode 100644 index 0ceba3e3..00000000 --- a/src/wroboarm_22/config/fake_controllers.yaml +++ /dev/null @@ -1,15 +0,0 @@ -controller_list: - - name: fake_arm_controller - type: $(arg execution_type) - joints: - - turntable - - shoulder - - elbow - - forearm_roll - - wrist_pitch - - wrist_roll -initial: # Define initial robot poses. -# - group: arm -# pose: home - - [] \ No newline at end of file diff --git a/src/wroboarm_22/config/gazebo_controllers.yaml b/src/wroboarm_22/config/gazebo_controllers.yaml deleted file mode 100644 index e4d2eb00..00000000 --- a/src/wroboarm_22/config/gazebo_controllers.yaml +++ /dev/null @@ -1,4 +0,0 @@ -# Publish joint_states -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 50 diff --git a/src/wroboarm_22/config/joint_limits.yaml b/src/wroboarm_22/config/joint_limits.yaml deleted file mode 100644 index cd2117cd..00000000 --- a/src/wroboarm_22/config/joint_limits.yaml +++ /dev/null @@ -1,52 +0,0 @@ -# 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: 1.0 -default_acceleration_scaling_factor: 1.0 - -# 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: - elbow: - max_position: 1.57 - min_position: -1.57 - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - forearm_roll: - max_position: 1.57 - min_position: -1.57 - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - shoulder: - max_position: 1.57 - min_position: -1.57 - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - turntable: - max_position: 1.57 - min_position: -1.57 - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - wrist_pitch: - max_position: 1.57 - min_position: -1.57 - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 - wrist_roll: - max_position: 1.57 - min_position: -1.57 - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 \ No newline at end of file diff --git a/src/wroboarm_22/config/joint_names_wroboarm_22.yaml b/src/wroboarm_22/config/joint_names_wroboarm_22.yaml deleted file mode 100644 index 159fc6fe..00000000 --- a/src/wroboarm_22/config/joint_names_wroboarm_22.yaml +++ /dev/null @@ -1 +0,0 @@ -controller_joint_names: ['', 'turntable', 'shoulder', 'elbow', 'forearm_roll', 'wrist_pitch', 'wrist_roll', ] diff --git a/src/wroboarm_22/config/kinematics.yaml b/src/wroboarm_22/config/kinematics.yaml deleted file mode 100644 index 05573e5c..00000000 --- a/src/wroboarm_22/config/kinematics.yaml +++ /dev/null @@ -1,4 +0,0 @@ -arm: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 \ No newline at end of file diff --git a/src/wroboarm_22/config/ompl_planning.yaml b/src/wroboarm_22/config/ompl_planning.yaml deleted file mode 100644 index 47312ca4..00000000 --- a/src/wroboarm_22/config/ompl_planning.yaml +++ /dev/null @@ -1,155 +0,0 @@ -planner_configs: - AnytimePathShortening: - type: geometric::AnytimePathShortening - shortcut: true # Attempt to shortcut all new solution paths - hybridize: true # Compute hybrid solution trajectories - max_hybrid_paths: 24 # Number of hybrid paths generated per iteration - num_planners: 4 # The number of default planners to use for planning - planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - SBL: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - EST: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECE: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECE: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECE: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRT: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnect: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstar: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRT: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() - PRM: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstar: - type: geometric::PRMstar - FMT: - type: geometric::FMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 - nearest_k: 1 # use Knearest strategy. default: 1 - cache_cc: 1 # use collision checking cache. default: 1 - heuristics: 0 # activate cost to go heuristics. default: 0 - extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - BFMT: - type: geometric::BFMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 - nearest_k: 1 # use the Knearest strategy. default: 1 - balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 - optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 - heuristics: 1 # activates cost to go heuristics. default: 1 - cache_cc: 1 # use the collision checking cache. default: 1 - extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - PDST: - type: geometric::PDST - STRIDE: - type: geometric::STRIDE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 - degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 - max_degree: 18 # max degree of a node in the GNAT. default: 12 - min_degree: 12 # min degree of a node in the GNAT. default: 12 - max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 - estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 - min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 - BiTRRT: - type: geometric::BiTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 - init_temperature: 100 # initial temperature. default: 100 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf - LBTRRT: - type: geometric::LBTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - epsilon: 0.4 # optimality approximation factor. default: 0.4 - BiEST: - type: geometric::BiEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ProjEST: - type: geometric::ProjEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LazyPRM: - type: geometric::LazyPRM - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - LazyPRMstar: - type: geometric::LazyPRMstar - SPARS: - type: geometric::SPARS - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 1000 # maximum consecutive failure limit. default: 1000 - SPARStwo: - type: geometric::SPARStwo - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 5000 # maximum consecutive failure limit. default: 5000 -arm: - planner_configs: - - AnytimePathShortening - - SBL - - EST - - LBKPIECE - - BKPIECE - - KPIECE - - RRT - - RRTConnect - - RRTstar - - TRRT - - PRM - - PRMstar - - FMT - - BFMT - - PDST - - STRIDE - - BiTRRT - - LBTRRT - - BiEST - - ProjEST - - LazyPRM - - LazyPRMstar - - SPARS - - SPARStwo diff --git a/src/wroboarm_22/config/ros_controllers.yaml b/src/wroboarm_22/config/ros_controllers.yaml deleted file mode 100644 index f8e4418a..00000000 --- a/src/wroboarm_22/config/ros_controllers.yaml +++ /dev/null @@ -1,35 +0,0 @@ -# Simulation settings for using moveit_sim_controllers -moveit_sim_hw_interface: - joint_model_group: todo_group_name - joint_model_group_pose: todo_state_name -# Settings for ros_control_boilerplate control loop -generic_hw_control_loop: - loop_hz: 300 - cycle_time_error_threshold: 0.01 -# Settings for ros_control hardware interface -hardware_interface: - joints: - - turntable - - shoulder - - elbow - - forearm_roll - - wrist_pitch - - wrist_roll - sim_control_mode: 1 # 0: position, 1: velocity -# Publish all joint states -# Creates the /joint_states topic necessary in ROS -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 50 -controller_list: - - name: arm_controller - action_ns: follow_joint_trajectory - default: True - type: FollowJointTrajectory - joints: - - turntable - - shoulder - - elbow - - forearm_roll - - wrist_pitch - - wrist_roll \ No newline at end of file diff --git a/src/wroboarm_22/config/sensors_3d.yaml b/src/wroboarm_22/config/sensors_3d.yaml deleted file mode 100644 index a4bb13e3..00000000 --- a/src/wroboarm_22/config/sensors_3d.yaml +++ /dev/null @@ -1,10 +0,0 @@ -# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it -sensors: - - filtered_cloud_topic: filtered_cloud - max_range: 5.0 - max_update_rate: 1.0 - padding_offset: 0.1 - padding_scale: 1.0 - point_cloud_topic: /head_mount_kinect/depth_registered/points - point_subsample: 1 - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater \ No newline at end of file diff --git a/src/wroboarm_22/config/simple_moveit_controllers.yaml b/src/wroboarm_22/config/simple_moveit_controllers.yaml deleted file mode 100644 index 044fd7a1..00000000 --- a/src/wroboarm_22/config/simple_moveit_controllers.yaml +++ /dev/null @@ -1,23 +0,0 @@ -controller_list: - - name: arm_controller - action_ns: follow_joint_trajectory - type: FollowJointTrajectory - default: True - joints: - - turntable - - shoulder - - elbow - - forearm_roll - - wrist_pitch - - wrist_roll - - name: arm_controller - action_ns: follow_joint_trajectory - type: FollowJointTrajectory - default: True - joints: - - turntable - - shoulder - - elbow - - forearm_roll - - wrist_pitch - - wrist_roll \ No newline at end of file diff --git a/src/wroboarm_22/config/wroboarm_22.srdf b/src/wroboarm_22/config/wroboarm_22.srdf deleted file mode 100644 index 97c46660..00000000 --- a/src/wroboarm_22/config/wroboarm_22.srdf +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/export.log b/src/wroboarm_22/export.log deleted file mode 100644 index 0f28f844..00000000 --- a/src/wroboarm_22/export.log +++ /dev/null @@ -1,566 +0,0 @@ -2022-01-28 23:47:18,488 INFO Logger.cs: 70 - --------------------------------------------------------------------------------- -2022-01-28 23:47:18,508 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter -2022-01-28 23:47:18,508 INFO Logger.cs: 73 - Commit version 1.6.0-4-g7f85cfe -2022-01-28 23:47:18,509 INFO Logger.cs: 74 - Build version 1.6.7995.38578 -2022-01-28 23:47:18,510 INFO SwAddin.cs: 192 - Attempting to connect to SW -2022-01-28 23:47:18,511 INFO SwAddin.cs: 197 - Setting up callbacks -2022-01-28 23:47:18,511 INFO SwAddin.cs: 201 - Setting up command manager -2022-01-28 23:47:18,512 INFO SwAddin.cs: 204 - Adding command manager -2022-01-28 23:47:18,517 INFO SwAddin.cs: 263 - Adding Assembly export to file menu -2022-01-28 23:47:18,517 INFO SwAddin.cs: 272 - Adding Part export to file menu -2022-01-28 23:47:18,518 INFO SwAddin.cs: 210 - Adding event handlers -2022-01-28 23:47:18,520 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks -2022-01-29 04:01:04,989 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM -2022-01-29 04:01:07,687 INFO SwAddin.cs: 313 - Saving assembly -2022-01-29 04:01:07,864 INFO SwAddin.cs: 316 - Opening property manager -2022-01-29 04:01:07,891 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:01:07,894 INFO ExportHelperExtension.cs: 1136 - Found 44 in ArmAssembly.SLDASM -2022-01-29 04:01:07,894 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:01:07,895 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:07,895 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:07,930 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:01:07,930 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:07,931 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:01:07,931 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:01:07,931 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:07,932 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:01:07,932 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:01:07,932 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:07,933 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:01:07,933 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:01:07,934 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:07,934 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:01:07,934 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:01:07,935 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:07,936 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:01:07,936 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:01:07,936 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:07,937 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:01:07,937 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1136 - Found 44 in ArmAssembly.SLDASM -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:07,938 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:07,939 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:01:07,939 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:07,939 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:01:07,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:01:07,940 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:07,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:01:07,941 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:01:07,942 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:07,942 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:01:07,942 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:01:07,943 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:07,943 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:01:07,943 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:01:07,944 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:07,944 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:01:07,944 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:01:07,945 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:07,945 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:01:08,306 INFO SwAddin.cs: 339 - Loading config tree -2022-01-29 04:01:08,309 INFO ExportPropertyManagerExtension.cs: 520 - Starting new configuration -2022-01-29 04:01:08,315 INFO SwAddin.cs: 344 - Showing property manager -2022-01-29 04:01:36,796 INFO ExportPropertyManager.cs: 422 - Configuration saved -2022-01-29 04:01:38,889 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:01:38,895 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:38,895 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:01:38,895 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:38,896 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:38,896 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:01:38,896 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:38,897 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:01:38,897 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:01:38,897 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:38,898 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:01:38,898 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:01:38,899 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:38,899 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:01:38,899 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:01:38,900 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:38,900 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:01:38,900 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:01:38,901 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:38,901 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:01:38,902 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:01:38,902 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:38,902 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:01:38,903 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:01:38,903 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:38,903 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:01:38,904 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:01:38,904 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:38,904 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:01:38,905 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:38,905 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:38,905 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:01:38,906 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:38,906 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:01:38,906 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:01:38,907 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:38,908 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:01:38,908 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:01:38,908 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:38,909 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:01:38,909 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:01:38,909 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:38,910 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:01:38,910 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:01:38,910 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:38,911 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:01:38,911 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:01:38,911 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:38,912 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:01:38,958 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:01:48,808 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM -2022-01-29 04:01:48,808 INFO SwAddin.cs: 299 - Save is required -2022-01-29 04:01:48,809 INFO SwAddin.cs: 313 - Saving assembly -2022-01-29 04:01:49,233 INFO SwAddin.cs: 316 - Opening property manager -2022-01-29 04:01:49,234 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:01:49,235 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:49,235 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:01:49,235 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:49,236 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:49,236 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:01:49,236 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:49,237 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:01:49,237 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:01:49,237 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:49,238 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:01:49,238 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:01:49,238 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:49,239 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:01:49,239 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:01:49,240 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:49,240 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:01:49,240 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:01:49,241 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:49,241 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:01:49,241 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:01:49,242 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:49,248 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:01:49,248 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:01:49,279 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:49,279 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:01:49,280 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:01:49,281 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:01:49,281 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:01:49,282 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:01:49,282 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:01:49,282 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:01:49,283 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:01:49,283 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:01:49,283 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:01:49,284 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:01:49,284 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:01:49,285 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:01:49,285 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:01:49,285 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:01:49,286 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:01:49,286 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:01:49,287 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:01:49,288 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:01:49,288 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:01:49,288 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:01:49,398 INFO SwAddin.cs: 339 - Loading config tree -2022-01-29 04:01:49,400 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:01:49,445 INFO LinkNode.cs: 35 - Building node base_link -2022-01-29 04:01:49,446 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM -2022-01-29 04:01:49,447 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly -2022-01-29 04:01:49,448 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\Tests\URDF_Assembly\base.SLDPRT -2022-01-29 04:01:49,449 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link -2022-01-29 04:01:49,471 INFO SwAddin.cs: 344 - Showing property manager -2022-01-29 04:02:15,278 INFO ExportPropertyManager.cs: 422 - Configuration saved -2022-01-29 04:02:15,279 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:02:15,425 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:02:15,426 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:02:15,426 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:02:15,427 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:02:15,427 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:02:15,427 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:02:15,428 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:02:15,428 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:02:15,428 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:02:15,429 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:02:15,429 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:02:15,429 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:02:15,430 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:02:15,431 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:02:15,431 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:02:15,431 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:02:15,432 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:02:15,432 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:02:15,432 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:02:15,433 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:02:15,433 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:02:15,433 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:02:15,434 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:02:15,434 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:02:15,434 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:02:15,435 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:02:15,435 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:02:15,435 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:02:15,436 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:02:15,436 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:02:15,436 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:02:15,437 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:02:15,437 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:02:15,437 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:02:15,438 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:02:15,438 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:02:15,438 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:02:15,439 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:02:15,439 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:02:15,439 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:02:15,440 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:02:15,440 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:02:15,441 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:02:15,442 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:02:15,442 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:02:15,443 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:02:15,488 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:03:44,437 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:03:50,608 INFO SwAddin.cs: 294 - Assembly export called for file ArmAssembly.SLDASM -2022-01-29 04:03:50,608 INFO SwAddin.cs: 299 - Save is required -2022-01-29 04:03:50,608 INFO SwAddin.cs: 313 - Saving assembly -2022-01-29 04:03:50,733 INFO SwAddin.cs: 316 - Opening property manager -2022-01-29 04:03:50,733 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:03:50,734 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:03:50,734 INFO ExportHelperExtension.cs: 1145 - Found 1 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:03:50,734 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:03:50,735 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:03:50,735 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:03:50,736 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:03:50,736 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:03:50,736 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:03:50,737 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:03:50,737 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:03:50,738 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:03:50,738 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:03:50,739 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:03:50,739 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:03:50,740 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:03:50,740 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:03:50,740 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:03:50,741 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:03:50,741 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:03:50,741 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:03:50,742 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:03:50,743 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:03:50,743 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:03:50,743 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:03:50,744 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:03:50,744 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:03:50,745 INFO ExportHelperExtension.cs: 1136 - Found 47 in ArmAssembly.SLDASM -2022-01-29 04:03:50,745 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:03:50,745 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:03:50,746 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:03:50,746 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:03:50,746 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:03:50,747 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:03:50,747 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:03:50,747 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:03:50,748 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:03:50,748 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:03:50,748 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:03:50,749 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:03:50,749 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:03:50,749 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:03:50,750 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:03:50,750 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:03:50,750 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:03:50,751 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:03:50,751 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:03:50,752 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:03:50,752 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:03:50,752 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:03:50,753 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:03:50,753 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:03:50,802 INFO SwAddin.cs: 339 - Loading config tree -2022-01-29 04:03:50,803 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:03:50,803 INFO LinkNode.cs: 35 - Building node base_link -2022-01-29 04:03:50,804 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM -2022-01-29 04:03:50,804 INFO CommonSwOperations.cs: 245 - Loading component with PID ?6???base-1@ArmAssembly -2022-01-29 04:03:50,804 INFO CommonSwOperations.cs: 254 - Successfully loaded component E:\Robotics\WR\Tests\URDF_Assembly\base.SLDPRT -2022-01-29 04:03:50,805 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link base_link -2022-01-29 04:03:50,813 INFO SwAddin.cs: 344 - Showing property manager -2022-01-29 04:03:55,199 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:04:02,915 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:04:06,718 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:04:08,432 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:07:25,776 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:07:36,624 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:08:34,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 -2022-01-29 04:09:06,042 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:09:28,401 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:09:33,716 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:10:26,057 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:10:32,832 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:01,760 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:10,262 INFO ExportPropertyManager.cs: 1136 - OnNumberBoxTrackingCompleted called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:32,320 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:11:50,721 INFO ExportPropertyManager.cs: 422 - Configuration saved -2022-01-29 04:11:50,723 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:11:50,809 INFO ExportHelperExtension.cs: 347 - Creating joint shoulderBase_link -2022-01-29 04:11:50,815 INFO ExportHelperExtension.cs: 1397 - Fixing components for base_link -2022-01-29 04:11:50,816 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:50,816 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:51,179 INFO : 0 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:51,183 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:51,183 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:51,184 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:53,156 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child shoulderBase_link failed -2022-01-29 04:11:53,162 INFO ExportHelperExtension.cs: 347 - Creating joint upperArm_link -2022-01-29 04:11:53,163 INFO ExportHelperExtension.cs: 1397 - Fixing components for shoulderBase_link -2022-01-29 04:11:53,163 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:53,163 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:53,164 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:53,382 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:53,383 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:53,383 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:53,383 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:53,384 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:11:55,357 WARN ExportHelperExtension.cs: 351 - Creating joint from parent shoulderBase_link to child upperArm_link failed -2022-01-29 04:11:55,362 INFO ExportHelperExtension.cs: 347 - Creating joint forarm_link -2022-01-29 04:11:55,362 INFO ExportHelperExtension.cs: 1397 - Fixing components for upperArm_link -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:55,363 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:55,607 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:55,607 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:55,607 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:55,608 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:55,608 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:11:55,608 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:11:57,637 WARN ExportHelperExtension.cs: 351 - Creating joint from parent upperArm_link to child forarm_link failed -2022-01-29 04:11:57,644 INFO ExportHelperExtension.cs: 347 - Creating joint wirstBase_link -2022-01-29 04:11:57,644 INFO ExportHelperExtension.cs: 1397 - Fixing components for forarm_link -2022-01-29 04:11:57,645 INFO ExportHelperExtension.cs: 1402 - Fixing 35 -2022-01-29 04:11:57,645 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:11:57,645 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:57,646 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:57,646 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:11:57,884 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:11:57,885 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:11:57,885 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:11:57,886 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:11:57,886 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 -2022-01-29 04:11:57,886 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:11:57,887 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:11:59,971 WARN ExportHelperExtension.cs: 351 - Creating joint from parent forarm_link to child wirstBase_link failed -2022-01-29 04:11:59,975 INFO ExportHelperExtension.cs: 347 - Creating joint wrist_link -2022-01-29 04:11:59,975 INFO ExportHelperExtension.cs: 1397 - Fixing components for wirstBase_link -2022-01-29 04:11:59,976 INFO ExportHelperExtension.cs: 1402 - Fixing 40 -2022-01-29 04:11:59,976 INFO ExportHelperExtension.cs: 1402 - Fixing 35 -2022-01-29 04:11:59,976 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:11:59,977 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:11:59,977 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:11:59,977 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:12:00,240 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:12:00,241 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:12:00,241 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:12:00,241 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:12:00,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 40 -2022-01-29 04:12:00,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 -2022-01-29 04:12:00,242 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:12:00,243 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:12:02,368 WARN ExportHelperExtension.cs: 351 - Creating joint from parent wirstBase_link to child wrist_link failed -2022-01-29 04:12:02,372 INFO ExportHelperExtension.cs: 347 - Creating joint manipulator_link -2022-01-29 04:12:02,373 INFO ExportHelperExtension.cs: 1397 - Fixing components for wrist_link -2022-01-29 04:12:02,373 INFO ExportHelperExtension.cs: 1402 - Fixing 39 -2022-01-29 04:12:02,373 INFO ExportHelperExtension.cs: 1402 - Fixing 40 -2022-01-29 04:12:02,374 INFO ExportHelperExtension.cs: 1402 - Fixing 35 -2022-01-29 04:12:02,374 INFO ExportHelperExtension.cs: 1402 - Fixing 26 -2022-01-29 04:12:02,374 INFO ExportHelperExtension.cs: 1402 - Fixing 25 -2022-01-29 04:12:02,375 INFO ExportHelperExtension.cs: 1402 - Fixing 24 -2022-01-29 04:12:02,375 INFO ExportHelperExtension.cs: 1409 - Component 24 is already fixed -2022-01-29 04:12:02,655 INFO ExportHelperExtension.cs: 828 - R1: 1, System.__ComObject, 1, System.Double[] -2022-01-29 04:12:02,655 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2022-01-29 04:12:02,656 INFO ExportHelperExtension.cs: 849 - L1: 0 -2022-01-29 04:12:02,656 INFO ExportHelperExtension.cs: 857 - L2: 0 -2022-01-29 04:12:02,698 INFO ExportHelperExtension.cs: 1352 - Unfixing component 39 -2022-01-29 04:12:02,699 INFO ExportHelperExtension.cs: 1352 - Unfixing component 40 -2022-01-29 04:12:02,699 INFO ExportHelperExtension.cs: 1352 - Unfixing component 35 -2022-01-29 04:12:02,699 INFO ExportHelperExtension.cs: 1352 - Unfixing component 26 -2022-01-29 04:12:02,700 INFO ExportHelperExtension.cs: 1352 - Unfixing component 25 -2022-01-29 04:12:04,927 WARN ExportHelperExtension.cs: 351 - Creating joint from parent wrist_link to child manipulator_link failed -2022-01-29 04:12:05,029 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from ArmAssembly.SLDASM -2022-01-29 04:12:05,030 INFO ExportHelperExtension.cs: 1136 - Found 59 in ArmAssembly.SLDASM -2022-01-29 04:12:05,031 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [CoordSys] in ArmAssembly.SLDASM -2022-01-29 04:12:05,031 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:12:05,031 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:12:05,032 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Forarm-1 -2022-01-29 04:12:05,032 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:12:05,032 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Forarm-1 -2022-01-29 04:12:05,033 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Manipulator-1 -2022-01-29 04:12:05,033 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:12:05,033 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Manipulator-1 -2022-01-29 04:12:05,034 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Wrist-1 -2022-01-29 04:12:05,034 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:12:05,035 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Wrist-1 -2022-01-29 04:12:05,035 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from WristStructure-1 -2022-01-29 04:12:05,035 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:12:05,036 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in WristStructure-1 -2022-01-29 04:12:05,036 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from UpperArm-1 -2022-01-29 04:12:05,036 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:12:05,037 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in UpperArm-1 -2022-01-29 04:12:05,037 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from base-1 -2022-01-29 04:12:05,037 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:12:05,038 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in base-1 -2022-01-29 04:12:05,038 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shoulder-1 -2022-01-29 04:12:05,038 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:12:05,039 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shoulder-1 -2022-01-29 04:12:05,039 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from ArmAssembly.SLDASM -2022-01-29 04:12:05,039 INFO ExportHelperExtension.cs: 1136 - Found 59 in ArmAssembly.SLDASM -2022-01-29 04:12:05,040 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [RefAxis] in ArmAssembly.SLDASM -2022-01-29 04:12:05,040 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2022-01-29 04:12:05,040 INFO ExportHelperExtension.cs: 1160 - 7 components to check -2022-01-29 04:12:05,041 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Forarm-1 -2022-01-29 04:12:05,041 INFO ExportHelperExtension.cs: 1136 - Found 35 in Forarm-1 -2022-01-29 04:12:05,041 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Forarm-1 -2022-01-29 04:12:05,042 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Manipulator-1 -2022-01-29 04:12:05,042 INFO ExportHelperExtension.cs: 1136 - Found 39 in Manipulator-1 -2022-01-29 04:12:05,042 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Manipulator-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Wrist-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1136 - Found 30 in Wrist-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Wrist-1 -2022-01-29 04:12:05,043 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from WristStructure-1 -2022-01-29 04:12:05,044 INFO ExportHelperExtension.cs: 1136 - Found 30 in WristStructure-1 -2022-01-29 04:12:05,044 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in WristStructure-1 -2022-01-29 04:12:05,044 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from UpperArm-1 -2022-01-29 04:12:05,045 INFO ExportHelperExtension.cs: 1136 - Found 41 in UpperArm-1 -2022-01-29 04:12:05,045 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in UpperArm-1 -2022-01-29 04:12:05,045 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from base-1 -2022-01-29 04:12:05,046 INFO ExportHelperExtension.cs: 1136 - Found 27 in base-1 -2022-01-29 04:12:05,046 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in base-1 -2022-01-29 04:12:05,046 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shoulder-1 -2022-01-29 04:12:05,047 INFO ExportHelperExtension.cs: 1136 - Found 50 in Shoulder-1 -2022-01-29 04:12:05,047 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shoulder-1 -2022-01-29 04:12:05,103 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2022-01-29 04:13:17,527 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2022-01-29 04:13:17,529 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue9.1830074983591922E-190.0156064900891439551.5715252581589567E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504422ixytrue8.02209898558041E-21ixztrue-7.374852413660824E-20iyytrue0.0044229329573873041iyztrue2.2568808327940613E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GeneratelinktruenametrueshoulderBase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueturntabletypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically GeneratelinktruenametrueupperArm_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueshouldertypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametrueforarm_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueelbowtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically GeneratelinktruenametruewirstBase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueforearm_rolltypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametruewrist_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_pitchtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically Generatelinktruenametruemanipulator_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_rolltypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically GenerateAutomatically GeneratelinktruefalsesDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalsefalsesDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==falsefalsefalsesDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==falsefalsefalsesDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAfalsefalsefalsesDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==falsefalsefalsesDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==falsefalsefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:13:41,728 INFO AssemblyExportForm.cs: 309 - Saving URDF package to E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM -2022-01-29 04:13:41,730 INFO ExportHelper.cs: 147 - Beginning the export process -2022-01-29 04:13:41,731 INFO ExportHelper.cs: 153 - Creating package directories with name ArmAssembly.SLDASM and save path E:\Robotics\WR\Tests\URDF_Assembly -2022-01-29 04:13:46,142 ERROR AssemblyExportForm.cs: 126 - Exception encountered in Assembly export form -System.IO.IOException: Cannot create "E:\Robotics\WR\Tests\URDF_Assembly\ArmAssembly.SLDASM" because a file or directory with the same name already exists. - at System.IO.__Error.WinIOError(Int32 errorCode, String maybeFullPath) - at System.IO.Directory.InternalCreateDirectory(String fullPath, String path, Object dirSecurityObj, Boolean checkHost) - at System.IO.Directory.InternalCreateDirectoryHelper(String path, Boolean checkHost) - at SW2URDF.URDFExport.URDFPackage.CreateDirectories() in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\URDFPackage.cs:line 78 - at SW2URDF.URDFExport.ExportHelper.ExportRobot(Boolean exportSTL) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelper.cs:line 155 - at SW2URDF.UI.AssemblyExportForm.FinishExport(Boolean exportSTL) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\UI\AssemblyExportForm.cs:line 310 - at SW2URDF.UI.AssemblyExportForm.ButtonLinksFinishClick(Object sender, EventArgs e) in C:\Users\Stephen Brawner\workspace\solidworks_urdf_exporter\SW2URDF\UI\AssemblyExportForm.cs:line 243 - at System.Windows.Forms.Control.OnClick(EventArgs e) - at System.Windows.Forms.Button.OnClick(EventArgs e) - at System.Windows.Forms.Button.OnMouseUp(MouseEventArgs mevent) - at System.Windows.Forms.Control.WmMouseUp(Message& m, MouseButtons button, Int32 clicks) - at System.Windows.Forms.Control.WndProc(Message& m) - at System.Windows.Forms.ButtonBase.WndProc(Message& m) - at System.Windows.Forms.Button.WndProc(Message& m) - at System.Windows.Forms.NativeWindow.Callback(IntPtr hWnd, Int32 msg, IntPtr wparam, IntPtr lparam) -2022-01-29 04:13:53,196 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2022-01-29 04:13:53,197 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue1.035828411313638E-180.0156064900891439571.9357498027169635E-18rpytrue000originfalsefalsevaluetrue0.93972387307473026massfalseixxtrue0.0025142902225504418ixytrue8.6586155170563642E-21ixztrue-7.3748524136608228E-20iyytrue0.0044229329573873041iyztrue2.2771129801693437E-20izztrue0.0021336882069818023inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueshoulderBase_linkxyztrue-0.0122586821821900790.1285772495779757-0.0037054435004292684rpytrue000originfalsefalsevaluetrue0.99636680500272734massfalseixxtrue0.0065237009420894719ixytrue0.0010646616036528998ixztrue0.00028312700527736404iyytrue0.0050231810993567032iyztrue6.82113719161566E-05izztrue0.0086334538259584inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueturntabletypetruecontinuousxyztrue000.035865rpytrue1.57080-0.25129originfalsefalselinktruebase_linkparenttruelinktrueshoulderBase_linkchildtruexyztrue010axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_turntableOrigin_turntablelinktruenametrueupperArm_linkxyztrue0.014397399905456463-3.2006162568792851E-050.27934838479492807rpytrue000originfalsefalsevaluetrue0.98521034391581119massfalseixxtrue0.023798222473833903ixytrue-8.87977733299251E-07ixztrue-0.0038853285623011904iyytrue0.029359472259760169iyztrue-7.1294436997127461E-06izztrue0.0062503483932010362inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueshouldertypetruecontinuousxyztrue00.180980.043071rpytrue-1.102100originfalsefalselinktrueshoulderBase_linkparenttruelinktrueupperArm_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_shoulderOrigin_shoulderlinktruenametrueforarm_linkxyztrue1.8457457784393227E-150.0550154986611603450.12015280303424725rpytrue000originfalsefalsevaluetrue0.51779610173045887massfalseixxtrue0.00404850874710771ixytrue2.1141942363467336E-18ixztrue-1.5487150407597627E-17iyytrue0.003755483293922739iyztrue-0.00037738536370652919izztrue0.00078832783822656164inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueelbowtypetruecontinuousxyztrue000.46634rpytrue2.493600originfalsefalselinktrueupperArm_linkparenttruelinktrueforarm_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_elbowOrigin_elbowlinktruenametruewirstBase_linkxyztrue-1.9428902930940239E-16-1.6653345369377348E-150.09870348455642336rpytrue000originfalsefalsevaluetrue0.30176308217533721massfalseixxtrue0.0021034428970283731ixytrue-2.7105054312137611E-19ixztrue-2.2497195079074217E-18iyytrue0.003050162507065583iyztrue1.8566962203814263E-18izztrue0.0010760910650178595inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueforearm_rolltypetruecontinuousxyztrue00.044450.2285rpytrue000originfalsefalselinktrueforarm_linkparenttruelinktruewirstBase_linkchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_forearm_rollOrigin_forearm_rolllinktruenametruewrist_linkxyztrue4.3021142204224816E-16-2.7755575615628914E-170rpytrue000originfalsefalsevaluetrue0.44770711794317625massfalseixxtrue0.00036770226690479489ixytrue1.7999450129153882E-19ixztrue-7.453889935837843E-19iyytrue0.00084342708626575322iyztrue-1.3552527156068805E-20izztrue0.00084474612356065992inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_pitchtypetruecontinuousxyztrue000.23716rpytrue-1.33300originfalsefalselinktruewirstBase_linkparenttruelinktruewrist_linkchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_wrist_pitchOrigin_wrist_pitchlinktruenametruemanipulator_linkxyztrue-0.00073032374046050341-0.000899365669252000230.049056009995342265rpytrue000originfalsefalsevaluetrue0.39742022555481077massfalseixxtrue0.0015968430526387824ixytrue-3.0724322789165625E-06ixztrue2.5323557993615128E-05iyytrue0.0016343224414687998iyztrue5.0029229087463509E-05izztrue0.00025632256399428705inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruewrist_rolltypetruecontinuousxyztrue000rpytrue000.096862originfalsefalselinktruewrist_linkparenttruelinktruemanipulator_linkchildtruexyztrue001axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAxis_wrist_rollOrigin_wrist_rolllinktruefalsesDYAAAUAAAD//v8ZTQBhAG4AaQBwAHUAbABhAHQAbwByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJAAAAA==falsefalsefalsesDYAAAUAAAD//v8TVwByAGkAcwB0AC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAJwAAAA==falsefalsefalsesDYAAAUAAAD//v8cVwByAGkAcwB0AFMAdAByAHUAYwB0AHUAcgBlAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAKAAAAA==falsefalsefalsesDYAAAUAAAD//v8URgBvAHIAYQByAG0ALQAxAEAAQQByAG0AQQBzAHMAZQBtAGIAbAB5AAQAAAAQAAAAAQAAAAEAAAAjAAAAfalsefalsefalsesDYAAAUAAAD//v8WVQBwAHAAZQByAEEAcgBtAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGgAAAA==falsefalsefalsesDYAAAUAAAD//v8WUwBoAG8AdQBsAGQAZQByAC0AMQBAAEEAcgBtAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAABAAAAGQAAAA==falsefalsefalsesDYAAAUAAAD//v8SYgBhAHMAZQAtADEAQABBAHIAbQBBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAQAAABgAAAA=falsefalse -2022-01-29 04:14:02,877 INFO AssemblyExportForm.cs: 309 - Saving URDF package to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM -2022-01-29 04:14:02,877 INFO ExportHelper.cs: 147 - Beginning the export process -2022-01-29 04:14:02,877 INFO ExportHelper.cs: 153 - Creating package directories with name ArmAssembly.SLDASM and save path E:\Robotics\WR\Tests\URDF_Assembly\URDF -2022-01-29 04:14:04,383 INFO ExportHelper.cs: 162 - Creating CMakeLists.txt at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\CMakeLists.txt -2022-01-29 04:14:04,384 INFO ExportHelper.cs: 166 - Creating joint names config at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\config\joint_names_ArmAssembly.SLDASM.yaml -2022-01-29 04:14:04,385 INFO ExportHelper.cs: 170 - Creating package.xml at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\package.xml -2022-01-29 04:14:04,385 INFO PackageXMLWriter.cs: 21 - Creating package.xml at E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\package.xml -2022-01-29 04:14:04,389 INFO ExportHelper.cs: 177 - Creating RVIZ launch file in E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\launch\ -2022-01-29 04:14:04,391 INFO ExportHelper.cs: 182 - Creating Gazebo launch file in E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\launch\ -2022-01-29 04:14:04,392 INFO ExportHelper.cs: 187 - Saving existing STL preferences -2022-01-29 04:14:04,392 INFO ExportHelper.cs: 450 - Saving users preferences -2022-01-29 04:14:04,393 INFO ExportHelper.cs: 190 - Modifying STL preferences -2022-01-29 04:14:04,394 INFO ExportHelper.cs: 464 - Setting STL preferences -2022-01-29 04:14:04,397 INFO ExportHelper.cs: 196 - Found 0 hidden components -2022-01-29 04:14:04,398 INFO ExportHelper.cs: 197 - Hiding all components -2022-01-29 04:14:04,618 INFO ExportHelper.cs: 204 - Beginning individual files export -2022-01-29 04:14:04,622 INFO ExportHelper.cs: 270 - Exporting link: base_link -2022-01-29 04:14:04,623 INFO ExportHelper.cs: 272 - Link base_link has 1 children -2022-01-29 04:14:04,624 INFO ExportHelper.cs: 270 - Exporting link: shoulderBase_link -2022-01-29 04:14:04,624 INFO ExportHelper.cs: 272 - Link shoulderBase_link has 1 children -2022-01-29 04:14:04,625 INFO ExportHelper.cs: 270 - Exporting link: upperArm_link -2022-01-29 04:14:04,625 INFO ExportHelper.cs: 272 - Link upperArm_link has 1 children -2022-01-29 04:14:04,625 INFO ExportHelper.cs: 270 - Exporting link: forarm_link -2022-01-29 04:14:04,626 INFO ExportHelper.cs: 272 - Link forarm_link has 1 children -2022-01-29 04:14:04,626 INFO ExportHelper.cs: 270 - Exporting link: wirstBase_link -2022-01-29 04:14:04,627 INFO ExportHelper.cs: 272 - Link wirstBase_link has 1 children -2022-01-29 04:14:04,628 INFO ExportHelper.cs: 270 - Exporting link: wrist_link -2022-01-29 04:14:04,628 INFO ExportHelper.cs: 272 - Link wrist_link has 1 children -2022-01-29 04:14:04,629 INFO ExportHelper.cs: 270 - Exporting link: manipulator_link -2022-01-29 04:14:04,629 INFO ExportHelper.cs: 272 - Link manipulator_link has 0 children -2022-01-29 04:14:04,630 INFO ExportHelper.cs: 317 - manipulator_link: Exporting STL with coordinate frame Origin_wrist_roll -2022-01-29 04:14:04,631 INFO ExportHelper.cs: 322 - manipulator_link: Reference geometry name -2022-01-29 04:14:04,669 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\manipulator_link.STL -2022-01-29 04:14:04,785 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,785 INFO ExportHelper.cs: 317 - wrist_link: Exporting STL with coordinate frame Origin_wrist_pitch -2022-01-29 04:14:04,786 INFO ExportHelper.cs: 322 - wrist_link: Reference geometry name -2022-01-29 04:14:04,797 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\wrist_link.STL -2022-01-29 04:14:04,834 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,835 INFO ExportHelper.cs: 317 - wirstBase_link: Exporting STL with coordinate frame Origin_forearm_roll -2022-01-29 04:14:04,835 INFO ExportHelper.cs: 322 - wirstBase_link: Reference geometry name -2022-01-29 04:14:04,846 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\wirstBase_link.STL -2022-01-29 04:14:04,873 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,874 INFO ExportHelper.cs: 317 - forarm_link: Exporting STL with coordinate frame Origin_elbow -2022-01-29 04:14:04,874 INFO ExportHelper.cs: 322 - forarm_link: Reference geometry name -2022-01-29 04:14:04,932 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\forarm_link.STL -2022-01-29 04:14:04,986 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:04,987 INFO ExportHelper.cs: 317 - upperArm_link: Exporting STL with coordinate frame Origin_shoulder -2022-01-29 04:14:04,987 INFO ExportHelper.cs: 322 - upperArm_link: Reference geometry name -2022-01-29 04:14:05,001 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\upperArm_link.STL -2022-01-29 04:14:05,035 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:05,035 INFO ExportHelper.cs: 317 - shoulderBase_link: Exporting STL with coordinate frame Origin_turntable -2022-01-29 04:14:05,036 INFO ExportHelper.cs: 322 - shoulderBase_link: Reference geometry name -2022-01-29 04:14:05,111 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\shoulderBase_link.STL -2022-01-29 04:14:05,189 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:05,190 INFO ExportHelper.cs: 317 - base_link: Exporting STL with coordinate frame Origin_global -2022-01-29 04:14:05,191 INFO ExportHelper.cs: 322 - base_link: Reference geometry name -2022-01-29 04:14:05,235 INFO ExportHelper.cs: 330 - Saving STL to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\meshes\base_link.STL -2022-01-29 04:14:05,274 INFO ExportHelper.cs: 405 - Removing SW header in STL file -2022-01-29 04:14:05,275 INFO ExportHelper.cs: 145 - Showing all components except previously hidden components -2022-01-29 04:14:05,465 INFO ExportHelper.cs: 145 - Resetting STL preferences -2022-01-29 04:14:05,466 INFO ExportHelper.cs: 478 - Returning STL preferences to user preferences -2022-01-29 04:14:05,466 INFO ExportHelper.cs: 228 - Writing URDF file to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\urdf\ArmAssembly.SLDASM.urdf -2022-01-29 04:14:05,470 INFO CSVImportExport.cs: 32 - Writing CSV file E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\urdf\ArmAssembly.SLDASM.csv -2022-01-29 04:14:05,493 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,494 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,495 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,495 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,495 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,496 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,496 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2022-01-29 04:14:05,497 INFO ExportHelper.cs: 234 - Copying log file -2022-01-29 04:14:05,497 INFO ExportHelper.cs: 439 - Copying C:\Users\Payton Jackson\sw2urdf_logs\sw2urdf.log to E:\Robotics\WR\Tests\URDF_Assembly\URDF\ArmAssembly.SLDASM\export.log diff --git a/src/wroboarm_22/launch/arm_assembly_moveit_sensor_manager.launch.xml b/src/wroboarm_22/launch/arm_assembly_moveit_sensor_manager.launch.xml deleted file mode 100644 index 5d02698d..00000000 --- a/src/wroboarm_22/launch/arm_assembly_moveit_sensor_manager.launch.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/src/wroboarm_22/launch/chomp_planning_pipeline.launch.xml b/src/wroboarm_22/launch/chomp_planning_pipeline.launch.xml deleted file mode 100644 index 97a44bff..00000000 --- a/src/wroboarm_22/launch/chomp_planning_pipeline.launch.xml +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/default_warehouse_db.launch b/src/wroboarm_22/launch/default_warehouse_db.launch deleted file mode 100644 index 198a981d..00000000 --- a/src/wroboarm_22/launch/default_warehouse_db.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/demo.launch b/src/wroboarm_22/launch/demo.launch deleted file mode 100644 index fb9b64ca..00000000 --- a/src/wroboarm_22/launch/demo.launch +++ /dev/null @@ -1,67 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - - - [move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/demo_gazebo.launch b/src/wroboarm_22/launch/demo_gazebo.launch deleted file mode 100644 index b8005362..00000000 --- a/src/wroboarm_22/launch/demo_gazebo.launch +++ /dev/null @@ -1,73 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [move_group/fake_controller_joint_states] - [/joint_states] - - - [move_group/fake_controller_joint_states] - [/joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/demo_test.launch b/src/wroboarm_22/launch/demo_test.launch deleted file mode 100644 index ff35c359..00000000 --- a/src/wroboarm_22/launch/demo_test.launch +++ /dev/null @@ -1,67 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [control/arm_joint_states] - - - [control/arm_joint_states] - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/display.launch b/src/wroboarm_22/launch/display.launch deleted file mode 100644 index 21a998d4..00000000 --- a/src/wroboarm_22/launch/display.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - \ No newline at end of file diff --git a/src/wroboarm_22/launch/fake_moveit_controller_manager.launch.xml b/src/wroboarm_22/launch/fake_moveit_controller_manager.launch.xml deleted file mode 100644 index dc8b90e9..00000000 --- a/src/wroboarm_22/launch/fake_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/gazebo copy.launch b/src/wroboarm_22/launch/gazebo copy.launch deleted file mode 100644 index bc973f34..00000000 --- a/src/wroboarm_22/launch/gazebo copy.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/gazebo.launch b/src/wroboarm_22/launch/gazebo.launch deleted file mode 100644 index d74221c0..00000000 --- a/src/wroboarm_22/launch/gazebo.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - \ No newline at end of file diff --git a/src/wroboarm_22/launch/joystick_control.launch b/src/wroboarm_22/launch/joystick_control.launch deleted file mode 100644 index 9411f6e6..00000000 --- a/src/wroboarm_22/launch/joystick_control.launch +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/move_group.launch b/src/wroboarm_22/launch/move_group.launch deleted file mode 100644 index ccea67e0..00000000 --- a/src/wroboarm_22/launch/move_group.launch +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/moveit.rviz b/src/wroboarm_22/launch/moveit.rviz deleted file mode 100644 index 53262e3d..00000000 --- a/src/wroboarm_22/launch/moveit.rviz +++ /dev/null @@ -1,339 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 138 - Name: Displays - Property Tree Widget: - Expanded: - - /MotionPlanning1 - - /Pose1 - - /TF1/Frames1 - - /MarkerArray1 - - /PointCloud21 - Splitter Ratio: 0.47119078040122986 - Tree Height: 270 - - Class: rviz/Help - Name: Help - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/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 - - Acceleration_Scaling_Factor: 0.1 - Class: moveit_rviz_plugin/MotionPlanning - Enabled: true - Move Group Namespace: "" - MoveIt_Allow_Approximate_IK: false - MoveIt_Allow_External_Program: false - MoveIt_Allow_Replanning: false - MoveIt_Allow_Sensor_Positioning: false - MoveIt_Planning_Attempts: 10 - MoveIt_Planning_Time: 5 - MoveIt_Use_Cartesian_Path: false - MoveIt_Use_Constraint_Aware_IK: true - MoveIt_Workspace: - Center: - X: 0 - Y: 0 - Z: 0 - Size: - X: 2 - Y: 2 - Z: 2 - Name: MotionPlanning - Planned Path: - Color Enabled: true - Interrupt Display: false - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - forarm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - manipulator_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - shoulderBase_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - upperArm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wirstBase_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Loop Animation: false - Robot Alpha: 1 - Robot Color: 150; 50; 150 - Show Robot Collision: false - Show Robot Visual: false - Show Trail: false - State Display Time: 0.05 s - Trail Step Size: 1 - Trajectory Topic: move_group/display_planned_path - Use Sim Time: false - Planning Metrics: - Payload: 1 - Show Joint Torques: false - Show Manipulability: false - Show Manipulability Index: false - Show Weight Limit: false - TextHeight: 0.07999999821186066 - Planning Request: - Colliding Link Color: 255; 0; 0 - Goal State Alpha: 1 - Goal State Color: 250; 128; 0 - Interactive Marker Size: 0 - Joint Violation Color: 255; 0; 255 - Planning Group: arm - Query Goal State: false - Query Start State: false - Show Workspace: false - Start State Alpha: 1 - Start State Color: 0; 255; 0 - Planning Scene Topic: /move_group/monitored_planning_scene - Robot Description: robot_description - Scene Geometry: - Scene Alpha: 1 - Scene Color: 50; 230; 50 - Scene Display Time: 0.20000000298023224 - Show Scene Geometry: true - Voxel Coloring: Z-Axis - Voxel Rendering: Occupied Voxels - Scene Robot: - Attached Body Color: 150; 50; 150 - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - forarm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - manipulator_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - shoulderBase_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - upperArm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wirstBase_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Robot Alpha: 1 - Show Robot Collision: false - Show Robot Visual: true - Value: true - Velocity_Scaling_Factor: 0.1 - - Alpha: 1 - Axes Length: 0.10000000149011612 - Axes Radius: 0.029999999329447746 - Class: rviz/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.07000000029802322 - Head Radius: 0.05000000074505806 - Name: Pose - Queue Size: 10 - Shaft Length: 0.10000000149011612 - Shaft Radius: 0.029999999329447746 - Shape: Axes - Topic: /logic/arm_teleop/next_target - Unreliable: false - Value: true - - Class: rviz/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: false - base_link: - Value: false - forarm_link: - Value: true - manipulator_link: - Value: true - shoulderBase_link: - Value: true - upperArm_link: - Value: true - wirstBase_link: - Value: true - wrist_link: - Value: true - Marker Alpha: 1 - Marker Scale: 0.5 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: false - Tree: - base_link: - shoulderBase_link: - upperArm_link: - forarm_link: - wirstBase_link: - wrist_link: - manipulator_link: - {} - Update Interval: 0 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /rviz_visual_tools - Name: MarkerArray - Namespaces: - {} - Queue Size: 100 - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: PointCloud2 - Position Transformer: "" - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /move_group/filtered_cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: base_link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - Value: true - Views: - Current: - Class: rviz/XYOrbit - Distance: 3.7679052352905273 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Field of View: 0.7853981852531433 - Focal Point: - X: 0.11356700211763382 - Y: 0.10592000186443329 - Z: 2.2351800055275817e-07 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: -1.1802031993865967 - Target Frame: base_link - Yaw: 5.961830139160156 - Saved: ~ -Window Geometry: - Displays: - collapsed: true - Height: 2272 - Help: - collapsed: false - Hide Left Dock: true - Hide Right Dock: false - MotionPlanning: - collapsed: true - MotionPlanning - Trajectory Slider: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000100000000000003a300000844fc0200000007fb000000100044006900730070006c006100790073000000006e000002e30000018200fffffffb0000000800480065006c00700000000342000000bb000000d400fffffffb0000000a0056006900650077007300000003b0000000b00000013200fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c0069006400650072000000020c000000410000002600000026fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067000000035d00000555000002b800ffffff000007380000084400000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Views: - collapsed: false - Width: 1848 - X: 1992 - Y: 54 diff --git a/src/wroboarm_22/launch/moveit_rviz.launch b/src/wroboarm_22/launch/moveit_rviz.launch deleted file mode 100644 index a4605c03..00000000 --- a/src/wroboarm_22/launch/moveit_rviz.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/ompl_planning_pipeline.launch.xml b/src/wroboarm_22/launch/ompl_planning_pipeline.launch.xml deleted file mode 100644 index f6aa6b50..00000000 --- a/src/wroboarm_22/launch/ompl_planning_pipeline.launch.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/src/wroboarm_22/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml deleted file mode 100644 index 9478782e..00000000 --- a/src/wroboarm_22/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/planning_context.launch b/src/wroboarm_22/launch/planning_context.launch deleted file mode 100644 index 9e6bc4cb..00000000 --- a/src/wroboarm_22/launch/planning_context.launch +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/planning_pipeline.launch.xml b/src/wroboarm_22/launch/planning_pipeline.launch.xml deleted file mode 100644 index 93a9ab28..00000000 --- a/src/wroboarm_22/launch/planning_pipeline.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/src/wroboarm_22/launch/ros_control_moveit_controller_manager.launch.xml b/src/wroboarm_22/launch/ros_control_moveit_controller_manager.launch.xml deleted file mode 100644 index 9ebc91c1..00000000 --- a/src/wroboarm_22/launch/ros_control_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/src/wroboarm_22/launch/ros_controllers.launch b/src/wroboarm_22/launch/ros_controllers.launch deleted file mode 100644 index da2ca750..00000000 --- a/src/wroboarm_22/launch/ros_controllers.launch +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/src/wroboarm_22/launch/run_benchmark_ompl.launch b/src/wroboarm_22/launch/run_benchmark_ompl.launch deleted file mode 100644 index 8773b211..00000000 --- a/src/wroboarm_22/launch/run_benchmark_ompl.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/sensor_manager.launch.xml b/src/wroboarm_22/launch/sensor_manager.launch.xml deleted file mode 100644 index bd976670..00000000 --- a/src/wroboarm_22/launch/sensor_manager.launch.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/setup_assistant.launch b/src/wroboarm_22/launch/setup_assistant.launch deleted file mode 100644 index 41910f78..00000000 --- a/src/wroboarm_22/launch/setup_assistant.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/simple_moveit_controller_manager.launch.xml b/src/wroboarm_22/launch/simple_moveit_controller_manager.launch.xml deleted file mode 100644 index c8236948..00000000 --- a/src/wroboarm_22/launch/simple_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/src/wroboarm_22/launch/trajectory_execution.launch.xml b/src/wroboarm_22/launch/trajectory_execution.launch.xml deleted file mode 100644 index 4c9ce3ff..00000000 --- a/src/wroboarm_22/launch/trajectory_execution.launch.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/warehouse.launch b/src/wroboarm_22/launch/warehouse.launch deleted file mode 100644 index d46aaeb6..00000000 --- a/src/wroboarm_22/launch/warehouse.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/warehouse_settings.launch.xml b/src/wroboarm_22/launch/warehouse_settings.launch.xml deleted file mode 100644 index e473b083..00000000 --- a/src/wroboarm_22/launch/warehouse_settings.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/src/wroboarm_22/launch/wroboarm_22_moveit_controller_manager.launch.xml b/src/wroboarm_22/launch/wroboarm_22_moveit_controller_manager.launch.xml deleted file mode 100644 index 6e73a267..00000000 --- a/src/wroboarm_22/launch/wroboarm_22_moveit_controller_manager.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - diff --git a/src/wroboarm_22/launch/wroboarm_22_moveit_sensor_manager.launch.xml b/src/wroboarm_22/launch/wroboarm_22_moveit_sensor_manager.launch.xml deleted file mode 100644 index 5d02698d..00000000 --- a/src/wroboarm_22/launch/wroboarm_22_moveit_sensor_manager.launch.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/src/wroboarm_22/meshes/base_link.stl b/src/wroboarm_22/meshes/base_link.stl deleted file mode 100644 index c298f6b589bed4d5547bebeb7d6d33a87c54cc6a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 11984 zcmb_hZHyjO8J#R7f~8vpexM12?E6wQYSI8kC_C>662%6M8d6AVqX{IG$|jbExRywz zu24%G(5%LfDzrO@3urV_qs`7cKxlw8SS++gBZd$(TKpgqu_k^!ANS0AX6Ig(AHIKj zy3aY!nYka&y?1Vw{eORdk#xVf^1a2LSKe0aU$?rPKkezf9^akIzZU~PHu2!zSHH3^ z|LE%d`Dq)U+M8A|3s^H{*$F50i)-$2}@6qkK!@avVIEzZ3DOC?8uHSa?!@0r}PH5=?+SS}tZ z1+#$N<1KIfPChlcwdg&zv*ZY{=AGHRqFi&z*xPgu)c@1TQ%wrX{)G$S-|cgJvc<4a|BrXL;AlOjjNP`S-|cgBeBNV z2}@NG+*ROE?0o^IVvf))=iT zR!gD^W&yiLmVLfP6%3I|Bh13z#bZLbU4=#>iuP00QWN{gCI7;sQgwKzO5RC4!kc## z%mUU-R^hZiYN?5RjsR=k&^MLzjd+Cq=qQ*4>>gp1)KU}s90At6VT@HW#(Gv0btHBa z%mQ|gFxqRWiG7X$Yu+$dDw!+dky0=V*ge9mt)(XRIRdPC!<-+=oEMLjf?2@s5voru zHL=eTV9h(T`Ocoy#G%wK@kl9{1>AUO-8B!60Bc_H)7l>1Bh=lFf?2>#Tj}~?ZN(8_ zeGh3jU86#Og!QANU>2}@NDt~dXnoERVC@g-e_dXvdX{_V4df})P0xLm1cj{Q7{YG zJ*2`FR1+8P;ZPs#?_PIf3XO1HV6Ao``>I`iRUW-?Z+`k$pI=b-^X{L`56{1YJq))M z$hBB;^1`k8lh1x~2?evzZknm>!4X!BU3_I;|Mj+r2P>F`{_lFon^$=AnPc-+Z`1p% z6@;m)TEv4RtXMYvKy||px9OU)=sj4$tnl|dsjvtu#-I6ab@K~*Cc6rLLwSkM<(~}D2%f*MlRhxP8ai*aD)}_`qK^7JGV?Pple{?^;5^tT3h{3XZVilneg5 z@Z$QrmryV(%*}{G`XEQINpI#@0i>Urok6Dun+PjpEyRHI;4@Tlb9?y9B=i?Bl0 z#2l+=^r=k2EZ%*z72GD=R-sl7x=+OsR$TDPtqb#aelOCxtY8+tYjiz0!U}zMSq&l{ ztYDUS>)9aw9<2!Sir-}NJsJhGqz(0K5P2$&utM5xGCp=$!7P~tdNzo7aD){ySMvBA zWCgQiHrw~aZhvru6;fmDD`!{15mrc*$dlEl$;B+m-OQWz*yRW-q}t`lD%#{?7SI32 zqtve;s6P5V33EliUt#y*=UUUO+GPrkup*4aa7txGXk9y#g}$*fAgkL?#gRn{I;FA) zD+D*J*Y{Mc4m}%AckICtR$%_?x5f5*u!32b&HBZ&t>8#_cKfEwnc51Dup+cV`0D%` z?_qOW`yBH|$3oj9JiGO6cys$wAl|z73AX@?JemkA!gvec09e5uoR`O2`>8m>3ar}t z{W7g!R(Pts`{tN~d=l2vZ)o-So7+4OUp8%pBSm^#S+0=RSg1<+ z!1iS`v|IeCv1I;hPNiIY(I09wk42@zVUjzOD7f-yHAZ>~#G1 zr{*~0C|~od2xDikCcL0!0xf>x;NI>e*CI> z`_8F8M}RdiPA~3}QZNhHJ;vr&)%U*tqWX&USM)gota)*IagUUOS-|eGV*5wxZ`^Wv zea^vNpCiDU7v~-KNGX^F>>lNF8|pPbdUiPetz$io0Bc^Hque80!jcw)MKdgG?y z8RvYl#}Q!7i?2q(BcWgxuzTp-$bNTeb@e~jPH+TR^Wv+Kd!!W10(Os=ul-#8@BMEc z+%r6Tjw8UD7bi>iNGX^F>>jf(ZK^+g(|v=t|Kz8090At6IDfiFO2I5(_c;3F_4Sxs zAB?S9UUCFj^WyyJ9w`O0fZgNJ^dI17k zSe*ar`jR8SnpbwRcCK}gl!95n?s4DlW5b{AxTfg;YfH%yV9kp&m3yQV%mQ|g_Y`*x z*Y3Hgc2}@NM$Hc zOE?0od8Mw{w;K0IDVPQ99#Y{7)I^Q|YhJ03_6^8AQVM1PyN6Wj0=1nZz?xU;ynQKh zkCcL0!0sU{PJuOwBfy$h)+_r`Bd}6x5TFVh&%`5A!-E6r>O2I7P;PKps z0(%CI0Bc^^KiG{~@JJ|_1?(QOlPR$G;Rvwim3@%itGP!?!7O0+kR4fpJsd}XHLvXF z>|V`1QVM1PyNB#73+zQX0<3vuUuw5Y?vYY33)nqmhdjWZnj^rPSN7L-yW}1z1+#$N zLw5QDoDDbvta;^}V7E)|ky0=V*gbG6(i00ufHg0leeB$oW#PUSk?xaZ+04lk6aG}D z2?}W+yM57!yocTPfE8D$8WC2=6WVpAT|N8XxMevwha3R$V`=BMkSV!Q{lxJ8sBzu>_;B>gk*;gCuHF2BfA>7SvHOm=VZ z+E2wSZV}BSzu>`p5#IYKW$CA41@F#OEx*WnFl%v(j1;`;^DaY^F8x%j;C+y) zW^s$S0194Tc|BLw(oe+--f^@&I2W_HMcN8p$#~`DOl<{6Six(1TEQ%Ck+y=@3|^zy TyRF~|D|i)6E11PCl4bt`R@fV) diff --git a/src/wroboarm_22/meshes/forarm_link.stl b/src/wroboarm_22/meshes/forarm_link.stl deleted file mode 100644 index fb511b3442ca5d1468b35914cc8edda55dd1078d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 19984 zcmb_kX^dt?6)lM)V-z$mnDB{g;yKl1Vpz~86=N|decJ~_&Z$5GF)w7CF ztK%Pj!0HX(Jue~dJK|OC3C}si^0<6PHAHu#YIdK|UjDG(&WD9h%+Lz8q71|r-gMaN zKYnv&;uu1x73DaBhyHFyd&%N98_VNnR6`jY#~yaX>i*;A62}littdy1t$*LyzU7|p zuZHmBk!mP|W8=0bto~=qA&FxMp;nY5$A7LoyS?M@-&qS``&U&%863C#`=HgmFT8aO zIfNmET2YQ1*FO3c?U#3MYD2hvNi~$=_l=Lad-9ptPmLqunAe@$?znVgd+NV7%&A5Z z=!Ki#@y!&~ZBKe>`-nFj-X3(%eY1*CEA&`<@TCc{>5TdItj$lgs199L4bk1GwqEqa zcFU7rVu+V7(+crY24e2a#mPy#o}M^{5Nbs^Wxn+%Yp*`@ZN_o_vT7)Ug4dh z?45-i!Z8B~wW1t3KKrhRu08l$A2N=smQ_PJ`n`E{#5qfeV+av~TJ3Q}=9rHh?Q#gJ zDG1{mmpqK47ok>^bFJoMt$v6++!r*I(|C-_cv!7^5mw!7MLBZV2sS?E3)f*h+zJ}X z;IQ!@qjzK7h7f8+IdWJhHr|N~yU|zKmv!Zs{mSDJVcp(Hw>ttFMOf$0mGk3Ck9X6h!+?Yov#Lm3=4&(D?hV+f&E zlp}|&IE}ASVe?2el)+)^)g0DZ$RP|N)QWQCu$8m%l{4Hjq6WS&np|IbJR)p$Ze(?K zc4!oV9xLnlsXyD^Y&m61^ZH9Zh8;jgsFm#o#${h})A`$))pL$*LO5!s&k7ON2;0dt zzLN>tu`kKKC<9@;nsK#TYPegX74lFk+eMABhl`opj;x70vUkq(S%ITQ*gkPS?h`M; z9xnT$4210&XR&{T?EA!Cgj!LKQH6yKGa+1OGw4F2V*r_Bpf$AJuplgwyi3*H>lFu# zCtH7Tb&6^Tp;o$QtT|Mpi1Eixo4o&-Ydsu_P%9k&(&8Tm5Y#B*%YQj#^5^qzz8{2I z9r@T}CMTTx%O1qOBYrUZw*!9T8jEC1KCE4ntM2GQs74XPc}yX4w#L0e?z+0FQNIr? z53?FGTaB>hP>mw2ZsWn~=K81=Je6}$`%0~B1jp=*VT5WFVLdkP?_EWxm7b4v=BiNy z&%t=sY94m3lL87QBjjPkdq^r-vdHeM0*g`%2ZUT zR@4ZGBUq6xhaEZEtS#m^9*in^@*JzaB6|ms^5_{s`jV(7kW)o^IH;LM*zaz=ejdh$ zQL7^CA}n4XIdCWfl|{tsBWM-Tu?xEhoCoGBcRQ=gbEO}_?yDnQkAnz{W)?mX70~_N zPL0M6IpyRY>M>UYts+{^58I91xoESG@AQEsjbf(yrMMB;Ew55l8Gt*WRz?!@6cOUUNQ zkK2gao#Q?PG{%t;lrhiWKLS>awwD7rU{%f>x_D8kQeb5vU>%SPjs}lzE&x zfGz?WMKHp2#S;1vYDJDbf}N<+2zusRub5w*x%whU8bQyzmm_NwVR9a)4u>MLm2vy= z-dbgi`dxQCGD5A$!Rj8k{Kt>%TD#{(@ALBM#urVs4umO+~s<(Mwq2{f+8UEI5;*hCJygiYSc=&y-RCEig#8K zka-*&7vLO3ty=Y^RxyuqZBQf9csK|BM!tgBzm&$@ITS$|9Eiq{o=1(KM*TwOar|Gc z27Ye|v!z+-eI~!7*E@@5O&=o7iL!FS3Oj)4>*moXue#LlKq0DfTz5;grXY4c;t#XS z7hlf%S2aiWrB?8SH7eyXg`h?e`=0Xp@gaX&?m?*LiFbTz{Jzt!$$8L|6?cF`5g$MQ zqVd^>+}OjR@v0S$;|_Fx9@HoTd}rMFi~B*S74o~~*}v^Um}WwaAtv-|QF+JoMwK;+ zum~rEnP-Grfup~=Y6T7%j{$`GQUvnrA9F>h6^;+~Zq_KmdTeE|cQc~4DxF{VmHEvh zh2GtE-d#Rw7S#jj5=Gz%#4FFayJyU6U&RWUv)}5dYE3~PCq_7oP%G4p{bq=Ir|-4G zECW7{0iuP>9a(i%lr?>b)Vp#o1HPCc<;16R$rOS;I*s6cc;r#8=wYP@TJd={cB!mV)Jxbt4L&Le4Xhjx{_rNrl>C>+-Hs+mUEnE3v2eFUw$rNFJ%W#*xQd5f-8E5d~3dl@YW;RO~lF zBo1m)=I$4A;`86@%oRbal=(on>zJpy`8khh7-h{t4g4ws72$clF2bz_qDq-tR32~Q z$Oyg5nK*h7v;vyvzgIWjZ@2xTW#%1?wTLoePjcz@hzJFNjES%)ePuw^Aqz)Bn5Flp z`h{#`9tejcs@bRFFw2}r;=?r+>NH)e zQeD@;N)d@W_U?3bGlEu$qdbYLqC&@U1Qo#!?N(P2v;qf4uy;WW%lVoD2GPKX9~M?v#AII26T z%)=41lJRhk8j-47Az~h754Tb82y;AARAnteG|a0;P@{e!^SJ%LaIfAe^0N}Y)GFn% zg1ov2%fmH_fXw6Is_tJQkBp$4#$&~P_gd8mV|I=Dh0NpNsP4mIJTiiE%%kk#YJ~Y) zfgkl7`3j=CpNPK72+ER&>uN-b#3J*4&1fD6e|2A!c{qYrG9K=sMx=^Xh{#v=i3jQ( zVU9PoFp$N6oXzN;`OBgS|BtY!u zDIc#9s!@b~Lotj{D~+~;$W>H?ehV^;sIAHuDqRG-8j)ZJfXwYI@bB)rBd8ihVEl=8 zj(p#T@1f%TZ@%{mnQzc`-wS89(6G9Y+0$KwY7}98EZ=`vm*l7vp;r9rqRYW|Xra-Z z_#S#MB7bYCh~doDms;^%?kxITxXb)4$Hsx^g=o!{k9gj#98)f`&g5cc|e^YE+VR3mClLGZozZd8g; zE9)5lrlE^ajUt9eP!VdyZx6a0I#OH>qE)GMow<&hBJ6zhRiewG2(_}Y@s**AP>mvN z1bsE=B5cg_7d%|sVWm~C^H7Z<_-=idLlJ6a$NgKGE<$G+euD)o?a(?Z)hL2rS9LiQ zp;ny1y9m`NLTgw@r3kgMD)@IgT@KYKLTl(8c@M|g8EcX4eeye^M0eLH)hGfo_g%vr zism?VIaH$v)@^-+T5&WZ;+~scJimJAjy8lFtODiv8J>CJ>D%+Zc-b7~c!%Zo=N{ZV zwW3@&_F9EQc>9uSC^HW{A1)ky2t-9I z%8_H6)#_HOu)RSyQVnJJMcwdxFmenb)QWQC_=Wj@w(;2gh8fjRhF^?7o?1qZA%t2{ zjvT2IjpJ)Gs-YbHe%qhEMtKMkf?Ad5sv#I+&AQzaYvb?l9YhWr^In8nQH~te z?X7p>=Hq8nLm7UpkNxe0$T5UaE6Rn#&p~_RNi~$22i{aD9DN8xMJvjY!)Auo=aO*k zl4>Z!FX~q2t09D1QH~ro!?ivqhPPtA%I`){1_#EUGpf&ty$H3U963_&wswAC-p%hu zP>%K4?QaW3c?e;DokXn4obTsH?`oh3>lAAmKc>@J7WwutD#n9 zjv7KB68cgEs!;fpLlL!AIp^yOhlV(&y8Gd;c9yx{(YDGD6{CfPx`7QfDU>r*` zs-YbH>R0hY2<%bHxAW!dJ_JLoMUES7C!?BzFh2Pzeh8sflyj}xSgQ&0$airlBM+;a z{5=4xRWCxVDCaS6eayFCfbno&&`<`4jlcYr0vq#Qgj!LK9M*}g_wK@`8P!k*hxM`i zwS^&sT2YQ1c1E>+4u*wA)lde9osaTYBZd%aMLBZV%+UH=5}t+gJm0OM3=Uq`LiX9G L7ok>^BgcOM>&LBF diff --git a/src/wroboarm_22/meshes/manipulator_link.stl b/src/wroboarm_22/meshes/manipulator_link.stl deleted file mode 100644 index 6bbdfa566555fda5fe5874ca1470c094b41bbe78..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 54284 zcmb__3A7c(wRRa3ClpZ#D(Dpv4wEv-Rngn$G&oNXj1x{zoDlOH6-2;@fU^-biN5Eo zQG!Qq2o4d^aQmD_9vBi)uZjkYW8(B2;)MJfMc&?3dv||zx*Pr1`rlfvw{!OX>f2Sj zYFBmN-i0y$fB!G|A-6X(G>b>}GiG_Isq6c}xKX!67hmv6ndM#EpH5`{{okXOl=Bg+ zX+$u3$8%;YqMbRGCLD-hD@MnYZfeWtP>pgZV&Uya2fzXSK!jQ;2lp@A4@PLu5y5hT zh-s`^X{@T$Rs@Jht@QU@o_xY_WDu-jD?})t^(r>)%&|1#K!o%>;&=cDAXK9qitys$ zd4&kIVl@Ar-*eTl6(U$x#L}uUO(mXR2fei*X$#v`bS}cq2G)?3C+oQJSfw0nrR*%L zhs2%88H5)DjV61mau$IcDr5hA1ZvR3Vy_T^R{VRuSEy+~B;%I#O50+D%H&}(B0d5& z4TvB=9)0HCADnRNyLNS6zv}j&d(Zc+eC?4p1XB-tCt0;=1oxi*NOa!hWmYrn!g>;u1O zdGUeUY+IfCx7w(2W*E_B=V0NuD2D?zh@epq^5cR1z&PU=`d*<15frCD<5Y}5t75NE zg9w@>fzBA80}*J2BjO`ag9w_H1ssS#s}6tLHMnXcH;;V|jNr;M#<#SOzdRF7AAwOr z#JF{LEqdAaFh7 z3Z^)HkIaCG;&qN~p;hsULJcBl6-1i({CFS&t#CE_2%HT#OL+Did*?rM#tJovFsHQy ztAcgkfj}#sZ{7QET+YVa(?Gk|{BEOQ@WY+H1A$gNE1O1k%t4?A5eIC!Ps=Hfcl!Hjm= z%9=5<2-F|~`FyWXgNRe!{c&yX3;S8VVgyd1eqI}K_fA%$Cjhp3`mZ|%H~oJ590Y0*p=XpV2O`jlybAKYLMz%o>XQ5qj>*dW8tIqA?6~zWMPuV8H{yriV_m>tOzN~_qF8E$`d2C+r;p*`Bsb|bYg|G(np{M5!8<;zaNM|tKS^Y7nuex+EI@>a6cVfYq~a zeHNYn$?_ZowiR#kY;^Te*IKJ$1Zogb*?)C3r}^?64n%lXcXzDaG3=@wgaHjA`uyPa zsK>$Qe+L4su6?0fZJUEXY|G9>)F5K~r>{l-JodO84n&|;@g9X5M7-Q(b@bj*BXT$p zfmV1j@Mj|CTFQ_1DV}>m8t!M=Y`I*7fK)aMN%K6y`5okqgKFH4us6j;W+(iUh70+GN zAOhElA9F;Y6|Ng&-alwc_~GSORE&AN)Y`ed#h80~)Bg`jLl?BPb{{qOdu7=czG69;?5o>7nHpax`WcQ|`$JuF7}Rz?wyqwY9PpubU| zCT*Aa+R}cISGfqZ0+~2yoMJat3#zCAnMb#c{A?MJ zm{*8ED~Vu^SExb6^ZU29oZGdM!+{9jD&4952;#2qBRbKJHadp`5yqreWX)?ZzaOAU z5yaP4*pCE(R@8nQ_c3>L6AdD0+@ivGBnY&^Y-h|KfL%|AY{ml~AKH`;O5pMxd3-j$_p$Cx`3TuczJM))Hz|W)7T{#uOpY zN@d5f?$+ty)}3FXclAq4s8N|YaNQVFgg`5m9mj;J7laq>eYf2?QKK?*;F>q42!U2A zJC3MQ2}?%|pc6nuyR*wUtWlXcFn5t%0RpX5b{u~R+bd14olP89l~AKHb6^fOrU-#n zDmxCdvn5&eH!pPWUD5NM^c(agSW!id%FID)B{^%^^^uD}E0rAwt=ibF^A%OpsLUL+<{`rsA<#-?$3gijcKK>{ z6*Vd|2jwov)I|uiQrU4(7OlH1dSDebDl-S}B{uKoB7Cbf9~Wn8L=a!W&Z$=H@8nHC zYWwxiKG8gHd+z#y=Mwe35wUNtaZx?|yG8qZEh5lLM>@+vbIG1@SVMD{cjGpe55Mx= z;E6j1MOlPq1J)2nK%Q7DT3zu(|B80=DeGWwUR%vW}1dgJ}c75Qe`v}w^g636}zoHOpyCbu|Xoa!yIYeXUk07jEoUc%W2=UOOeGWvR6|NN@ff_`} zNat`M0HUcpsMPUL$<>m$)1LgbtbmxHiY6sKg=eGb%MyW(w5&k=!E z7#m}*8FGJlS<`Oev10;yURzn6QQy5hq0`Pa9G^RmECrkWv9JBzm|y?v!is6?X%VPF z1dcSF*adMMaUcS%#!kC8c;at62**R;EUg^+aL14ls6hnA-u&)*4VZ}|h^ z_~V~93d7Iet}q8`5aEy2!-N=~gFvgU>pGT?IdfUSV`$9Kt9A&NmF~41s6hnA#+c>; z1X?vs>RBEzVX|=CF{W=g@vGjJ12u@i8Dk71F33Tk)zDw;RzB+5`&(Q;&OB}R&@^w= zkH-o%h!EMX6=N)7a3R84NlR^xL;6t%4y(a-rB9K|KGKg20Eg9uqG%Hh^W z27y+x(uCuBTD9wU>S+S%;kb+t8#VQeIhP;;tz`WR$5hHbPd4pl5vW0gF+WO9 zvc_EP@>K@mTMg<%c}zH_47tBX8P4{@7}TWg5+6VBNIxhiT7=7qDFUs?+lX?aa8ORH zQ%+Q`5)C3~-1wh;pKEP|WL;6Ez-*1`!m0IQvje%tfFT&8vuV zqHs`7jCJm!1`#xm;S5J}H>R9u=Pn}9idI35a$>p$W6Fs-+Y=2UXg$JNlyYJ&0Pv;qU0;eaIv{!^H#}Mi3SlO+r8c9 z#MsO%L|7}~ki0AXr~rr6V7t<%Ajyf`j|>8>WJH1_C&rW$Edn)&kk|+Z<;0kBVg`X$ z5_93;S)zL_Y7ilFOgLm-Sq?;?mCUztk`wEc6GO>~Jgcn+5wcd4!>x}D0%)J=+;W zInkc_c&zZ$hX~?>=jd*;ZmF;7-8+8bnC2Ms(wQ@EjK==DL+!_h4XWw4kt`cCfbD_JjDyKYvr-ct~@M8br_+N%qT3huHMP zE#uO|U)6syW%n30i12gby{~tQKOXY;`tQazdkD0;$JX+tp zZ*zIHG=80EUgY9Y!g+pw)t~oyZ z{5>k~O&JuU1`#rDl6U)z8W8u{VM1l~dCeXItt3u?<5>OIp7HtrnqB$Lw?j38R)dID zQg7lApHAu(Uw_XZDpLmzj!}aMnPcMBFVEgCK4$vz%Hb26Jp@|GoEEQ!Y`R5!_hlbd zp8ss9&UULo1by9VD`K2iuT0t^e(tAVRDSl=;21TCko72e_ng|AdbhrtgaaovdkD0W z^)Fs^Yk#hO)IYj}m%lSqGlSJ2LMs;}f_pw!KYiAA;g^3K5~BtYxUU$~?X`LJ1#5N= zXI*}GJMXd%ATDjm5Uw(RN{k9_qg!}$wj~F$Gz@5mL z5yOVmo4O7TPnz89A<*itZ+4C1&36#5p83;*wX@%C4o9pQ8lwgg#yp?Ae=z1fLYza0 zas$G*T43vRTtA-s(}QJ2(AQ3&N!ukpc$e`OA;ybWh(IgyHc0#Nr}CwhwWs$Fhm%({ zKFK=^ia|j8pzST9joD`2<&|mM4G0H6v`35@M9`?)x+2#P8r_PHE+Wv%_iE5tn}y>Z z{Is$kc|~(6dCNhwJ$V~JE2>QUhs@nEv$qWI{`S+#N8<+bib^#4jW~OPEg3`WqoV5r zHHe_~5zx*l9D8l?Y~>eU{WuI8yh1A+Lu2-uxUw>Tao6y|8-{qJiwLbya$`m7qoV5r z+d?ZGX=6V7cyRdign<=~Amym!O$uevN4#glBu6Pdhc*$$DWlAn+)XrBhl!0 z=3rL^k@?dPHH=hzln;as5eF0H|zJ@{#zXSNycLh>!>h$6GY7x{YnM5kv%9VKnIt z$%5YD_4m~4rytZ`*N5!~BJ_KDH&%2`4E3DowI$!svlY$-Vwc{h%&dQSE zYL4T9Z_laRcE&#O$RkR;e{e>&8m)q0D{P5&&RMrq;E9DZwQUy>k{N_!PnWM^$n6$^ zRv1lVF73CX(tS*?`1ooc&AS9(DO${pFglIw8FVSe+4-H?L z7`<(~ZLiwz&e$`4=n#4~fVXNsV%I)YMJuB#yK~I@IU!*hvaYQn*7A)4kGKSvA4X_KRRi#a#k zbl3lgP=g3PKQgy5$NuEAdbcZ1C5{`bh(IfqT|bVP)H#0mfFlV}t)fO{ZkJ{vKM4m8 z@#KWA@w{z*65c-Vw-IU(p=WL9RnwKb#oc!;6UReUM4*+*j^o6w_ls{{TOveMMUBeb zE@dKq5*DwP3_dU(wac#IjdPxgP=g44E^%J{andnyr=zwaj^$NEpq0wbs{tRM5%0ar z+w`^J$|`D9=5{H=@sqH4RlVk{c&~R?SB8E4S%exy=rf%2>a}ST;txM=C64wgBG5`@ z=T(OCD=rZ|5ipRg`lS|bri$E)tomUISOpY%)Xci$BR8gZcw=1JAJLfA0ToAAQ@!j>N+e@AX z5&9m*d9~gA{}WI7=+DG)r$*4VmDa)56ydzO;k}dNtq)yKi2tm58bHVl6|V+3n)%8d^;=h8 zKnODjH7awvxbIT&*eTQNH_o3DZ+!fIo(2)Ri#o5K-MFRx=Z7yQj={aLEwobEd3EKj zGiwh_pFxNPy-}mGYd76@$@?Co`i**YMts<%`_pccY7jxP*1?huag-fLN2*=&5Q&u{ zoLA%KuC2^DW-NJibBTJZRk1aShgPp9vO^sCyG_Di$(Z=o<#Rj@#fG1@ZJes(LU%ud;WpVf5*Yeg=_gVuTI*7@=ht-C~%hj1JhR|bU- z-9>LYsh$%NDzg>F#+Vm=wRgDRq#^Oa@BEjiK?G%nRG=dsOK5sFfZ<(QM`Q$V8gpxK`M!S9aG& zZ;he-Jaqf{(h_RKD-YqkqWwIS{oF$+nys);be_ECtWeKBbl%as1=RO|5$LTkboL3| z*=J4(HPTxT;k=@=Pw37*4|xbhgIBgs#?U!2)N>-84fQq~T~U?;y`@|->6p-+6R#+t zMrMYGa9+_lF?8p|J3WM=*$Vq)44tV%JyX*;T5tZ*HwBghy`>vcuiPzkXX;@k)X0kR z5Y8()Q-|(MJ;p;Qnys);#?bReMV~+DnM3b9;$1X(%Zc9F=Z}he{#e`_HF*f<6+M51 z?)k%%5TP<#VV{iY`pVkcfS%JsGqYD!_Ca}GS_JQU@yUx2Ws5MsrrIUcqzK8u(h@!0 zRrKi&5om=YVxJ%@?g{dqIjG4)xSrGVV8uNTzR?R2Dzg=ioBa}y_Shz>J?H9|v>%Fa z`%)*eSv<$dbTUp56lc9FtVW}&_aaf|EJC0L5yYo=BoP`p5aC;;-uej2AIa&SR;}JB z_C38q1g$Q;|7-(Zp%spZ?-lK2_Aj}16yX$({qqr?1`w3B_0F0Nc!gFtB0dM54fHOp zRZrCfd@;?`*(3^_HN=7$_!`Gw;tr5t2g$T5g zxsbzw8boNVLzV*(Xod6GpSw7hv=WWm6>llJ*?E=DI7DbQ*MsJ7qZ#p_NZ;MgJwM*^eM< z5J7oGD{>pWLIhgjn)ho)jTvj#1br78;EGb2f47zQN$o3YROWu*nlDD6mCB9-D{@hz zGIRL-C_%8mnTkx`>EbKto7wa9A4ZK0LQjsq*CQKK?*U^H#5eo}?4R@@d^sq8qg z(i=4@GY8H}zcyU0xGl6&*>PaSI%-sA4qRQfRzIn6S1WD{tyFd#4VCv=A=!v%k-J`a zw)@rnh)Ar6!^%lNDthMtYE+i7vQ@t<`*#kg6}LrwN~~0N9C#A~YEfeg@ zWq9qHRw_FVyjuh{Ds#J(yR^pLWw_)v61C#C&`M>;fj6F@MrG%FdVcUL z@72n+g;r@kF3!|=lA)Fg&R3Y*;XCc5PmUXRXY>jY^yRu%PVyRrr#nQT6^>yBp*IBt z@U=R%i#Y7imgX3;(eBG8I5YDBA-YknFyG!L={vl@*8R{(QuP6GnlmEKxUiaAh& z2pPAWejoy^FtUEnQG*DHW`55bXNk4K`1>5Va~ktaN$#0Q_V(;pVayRBb2q2wh(Ifh zzwedq$jnYwdhZ8&1!o3aAE-fufA=jmfS5lYC6>c5^t>`;Ttz#n&sY|s8)F6UJn(I=9L+Vm92(+Sa zBejB$IHWF>s{#2t%S3|+8fmUe6%ME$^blx8-@|hCDOaTs2Uj&ptv-Lhn`jV0vEjN@ z;gGsi>lGrCx>VtSdQSefHqju0Vy^e%(E5a zxGt5ybxt&h5LtEuix^ypuvXF%fBj7y(vLcDSPix-eTrQ6k$z+lXeIsQuZ<-hQme0H zWi^P9*a(NzrCJVb3#}wh!Xb637J(W>$Q%<6nO7METFDIMFHfl-ygsB>UuUA#AVSuP za-?B{t}(-i3Sn09^qUf_m^Z4Xhmz2t8RpYG6UaVViBl8 z1mzXIhsWhazP}`cKr5-)kbGrtBe`O8zQ084KQvz@?FzcZ$%&!V>T7L=)gVG*BOG#niRHky&`M%196U=xcgu~| zu~-cvWR3}k%qz=*ZK0LSw{nsb`TmlSdyX1J$XZd3^nM=?fmX5xg+uNyu^gyDgsget zko!wQ$%(vbZChw1>t8tJ{t}Bo4I=O@MRI>h2H{(!XFHn{?WvE)3Qv8AAU?joMEU`h zFCpe7_y)49f3K%+O(>U8t$syn^*sbyVdkTp_)1)nTKy2)MLzv&xZ|K&{fgA;hp0gW zW+hvzueCBB0W5ORAEE{k`uBS071ip8QmY@L1`&Qvgc>XlfmZPCAbCZ# z`k~b7hp0h>es|!!qFVh>YV||ZAOdrxt<~2WEDwQJ@a-UZMYZ~&)ar+*L4LJhyz8xg5s8&CeT78}E)+W8R7 z1nw)gR$pt8Jp@|8cYWj))#_KIR$sFye}`B`gnpyryrNqDiqz_ds6hnoM7CC6tI0hC zTEVx9E1_tT-7Ksr&|4* z)arW(v?6c0Cen_ftun1ktv>H+$vX>*f!5lU5p8Sr>r$&9q6QKAb)$<1+=SpE(8~9U zYV~8O)emVdCGRq5wkPi#Xhms-8;up!>c>*6&nqg?&|1+OFUr`Gt<~4NEIbZG(E8BY zKH{KS{kqiZdkD0`F|@V%b*a_&Mi&vZZtT~lZmi%g3lD)-IMTLOKbBhkkaAS=zJ#)9 z@?L{7wN|)MKd4qemRfzz)QN_2u>Hc6J;9c2t-juo;&C8?@~+nQ5eL=k$5N~BA0Xksnrirg9ysU_A6F5R&Ym(hd?Ww3$|82mRkK##;1)>+tS;JW#Nk)2i5AwQmfDV z2lvowXm7V)uCf)jWNY>H?j4T<5i;s+j)Q9TW2)6}rJ8CFfmRqzW2ja?mRfy9=#I?M zwC&P9uebG3JmBsf4}n%V7i_J5EVcSNx^{eI71emGWFE^{QLTO~wfek&@XE0oIy36c zPi2X$ZOPW^>zz&>2O=bb!a=qAvDE5&2(-dz+FE_Od&k!5>rAxlh@kVM{r5RtJm5|z z4}n%V7m_T>wfeeh?f6K3w6bKln&Y5a{kqiZ^KPJ3>io=Mze8p#$t4zTYxVVZF^>Zg zk{N`9YV|o^ajm|GKr4)%4y?8bs)K&(15V)h|n}zK8Iw`og<2s?{$`tv>CXsm4ci z(^`F6QL;O8t-gn#NF`Pne_N|xlUjY<2Q{_{LciH|{eW8vJOo?y3YNd8rBZdb-l zP5@BN(W0j%`a-$E%AG#=cU!BUsmPzR}A>5i;5k!5{1 z;Jm^*Nb$-d&`M?JRbCw=Yt)L{l~I?S6KY014I=bCit`FQLTO`wfde0 z5&C}4d4)B+*cMu;?7X5{{m|9w-=0+cvPP}AUCDg1pHr=VMQZgu4I*?$bzWhmH@1aV zDm$;JR=?tE^~WWZ-mFn8ZWs4mTdQA@T76H02;D`US6JzdZK0LQ&MW-xRrfw_OJ%lF zgyZQ@@ zt$yrk^@k;QaxjOY*$QK0YxQHP)%P@rpw*l_$=F)`_y{mdpevQop-d3R(%f`f!^9${p6k^)JShVg!3xzo+9>2(cqQsldaX)JDmbL8*25kt|-fa z-r8FIbm@MUBeb?wYR`21ic0S~!XjXr;2_n0Cv8`d72g zBMx&PYE-ry)g{63S7!-FAp)${i0nApZ~LZvTZic}6%LnBqcU^En>-s_eblwWQG`G% zl^w^4gSQPY>GMzh>G+!Suv^z`tw4?m!ouPC8LW#;Jf zgV%!|2cIt-MF_M~*>UW!enxozJM(BYwUSx1`KjT5 z&Htpr|8g&CRA!EsyQ~i0J8Fb*6d}+`Wyi7PtF6P9`A3EHR=hWARA!D-mOT?3J#wgU z6d}+`WydjV|98tToJ6;gnCtFCjmpe%m-anlA1M-c+8RCXMPzi~-;@Vy(;SS>A~ zMrG#c+`lzgc>B?TkC<@STZ2)9h^eD~8{Bll!hq4nFvmfbV{r))Xr;2_`1qE%a^<+6 z(`>)2gc_B(-C-Bb3tk%0CLBcwv{Kn|?0DM2;qAZaK^%)qs8N|Y_MZPpaNgu)!cl}k zE0rC`?I%wQdw)EDR@BN8YE)*9iElg_9CGUO!cl}kE0rC`%EKpw^L{jsA~?5%8kL!2 z?Tm+mE^V&~M-c+8RCXLazUdntKXN$D#9<}WsLULF=H4HiaO%6lQG`G%l^w@FdLCC9 zeW?3az)_e1XB-tM>vWQ zXr;2_`0rPT#f!TRA&$jW)TqoHokv_5Y`^jq;V43&mCBA|X?;q3!k05C=IvF~sLUMQ z)?6Aq)w^9diV$d}vg4pLLo0oSMg4gHKGHbnX@*&`M>;L9@N$*2nN(s8N|YXstx)8Z1JfmCBBTR&Cv_ z^MiN|+O}AuGIP+HkJ4OHgg`5m9S3Ef*yXDQRn(}=9F)7FG$$4z&`M>;L0L3*d3RM6 zH7YX)<=`mI?L`Q*QrU6PZV0=T}jqGIP+L z7^Qn{5dy7Lb{w=j*WG^J=|0q`%pA10N9mcN2!U2AI}SQ!#O{>QUPX<{%t5D*$UDiz zeD)dRPBMuG5p=4F((@H_xYH8lU1$rfRCZp`iL7SNa5H;WQKK?@Md!IFJtr0+&`M>; zK_|=DokeF?QKK?*(77~9&$~qkv{Kn|&;K~G+>dsgdI zMUBeLLCKKr59U2R%X7>@%mit~Y8_W)6D(jMC@YA_Q8g>^SI2xZ<9jr}J~I zZHqN3TaK?6M(Oi;Ap)%E$=f0v2R+e;?j6A6CDf?Q9P~aQO5ZaSA<#-?$3gEhLia9X zWeGJZGl#wjVVS)R3HGb`7rDsNIuYJOokWcK~X|8kHH%EiD`u zNoL4HpcTrFBby@^p?J{EafnT(|_`q$}Lt}~%Xr;2_c;K9E!Y&W; z8_0V~s8N|YR-Q4wrG5P6!cl}kE0rBb2X~upY#!=WLXFDIF>c*mi=I3A65%L9pq0vw z<1aTnTHohnek1(G9Mq`H9E*A_Y8!d;b;41EKr59U$C-DB@z0jb{zjrG2i#(^N3@n zjR#w?MyW2((h!arCCS+n?`_rnj}IQJFb-9yg8bC>%uyv{Kn|JVI-5 zn+JbN9Glto!ELcdt(b$?WB2|W3r7(GtyFd#70M;UKKY0uc&lCK+!kxpia9Xz8B>Hn zE0rBbUKVAIS}_OBF`H2x!k&3d6WusHGgM91lbO|Ywih9I4yYCLajxW+?EXRbUpo$t znr0au-88GEXdi*?B7(;)&AaFoBG9VXtHyPg=8x~=6|X2oU?wW=2U_8X_z0ZgxT3Is zJ_0p}z%^ftKr0*(AAxfT=Pq*l2-F|~S649tt#CvvBDpD@p3m&x0eM!_^Pv5E9m`E! z-w$?ee>zHLdxFS&&mf58jfKxaZ6z9g&%g+MACTqHCsWqw6QpwFd&L~8L4-aVW;qan zR>eI>4I=c}Fqb14MYPfoTb0`9>a4z^9G?(n(8o4d}J06XQ{X1ut12u@Cegyerh2u`KvELVP zyBH_mE7Tx@;%~nk$a;kcv|_JxM0^g^AcAJ4{c<47;UT~Z*T2t!*?{6<|H{toVoN>( zHHe`2+rOW0*ekT+mh$6)8br`Mwtqj*=g_v$3g-g#1OB>19LdU2`Qi&cX?Rw5iqZE5E5rZSlMxmKJUcPbR5)g z*6NL8=7=ZV)b{UDOUj@0A5do59RIQPYTT$>BL1Cj_-sI^1`#at?~JB@oNEj{*-h); zI_CXt;s@uRUt>*t-c}WsnS*8Gj`;Uoo_wMKftp4Hqa6Yx$OzWxSg94F{RpD(d84q| zc|GXNiX4hy4I)%#ZXdDR#L3pH!`C-e{_~U@tUTkTohw^Szst%mUcE~L$7e_O3)uIb zL66D@oLM4*-ae#UfrLWcE$8blP2E+WwCptly-eq`f;vq9yjPw#AJqRt+_AJlH7 z8blDc{XN?cM4%OUm9#`0-;R{OhJSb;#^d~v*I3{COxoFtjgP<>AfoNi6D_*_@1}+b zA_A>&zWF`J`Ln~p`|iu55KSBKJ-tE%f78V1*AE}eUO~^%E3~5D+Zd5M+d-4IOMHve zL%$!`7FtpNY)jeoff`y-)=JhOaARgb4n)xC+L-fdF7^toUjLtw7V&k@of{CS!MuXp z#Ts5l_ z8O|DB2fRL5<`u;&jpZcoCJ1I{4Rff>zO%RdJ7)>v_;#cqKJ1MeMDQ3gBAL4h2S<=K z99xb#%RDoR5vV}~&oM^xtn_=12(;ok&4^^SCth*pWR0ExSjH1Tl0`EJ)^Mg)gv!az zxj_V5VPyS&=;$_{6ZCh92b_IS!#S9};&Xz^*?#09*h-_BI}>fYtig6Uw=-XsgR>}W zc-$!-R@VKTf6vYmilDV(4I(K1Hcm+{Nk$iA%NdT_l}v48p39MF5JCSIcZtzSrWTG5 zd*i%9EA-Znpsz{WCBA*t!(s$l;TZY|&T8BipRaIr@mY(1=d+fNKn)`N{!wmEMi&ui z#o3NIvbh8`h|qbJtj{8h zkX+J$P)#0!(Z=+8bcfh%|M}dWj~@|ooSB2ynj*Me{+(NLYp@Za8bq+H+%$LjZ}ajF znIoti$j85HOId_!8W6r$q3Qc|U+xD-kU2OzBOgZA_S{1-M*=Gh`^IYBZASA+hLZd z6|V!8nS*8KkoD1kP)#1f&E4JYy!v`>_s5TjdEGHPXBkCsySN^WX+$tbBf|G;%e6a& zX0w0yy?N519tXCICntIkEy!5njFAJ|_4mOd1X{7o-nvuYZm~k?z_emA<&9t z=HL?t-MQR!No?8=Z=Ez`hdOEyf#-)}gm3i*JV6piXf`>#A9LVSBmXPyJkor6A-?1s zWI1vXXvK2c59)bnb{^J`#|kxwpmDQVG#TAo1X{72#)Bdlnnhjuam-PJ2#UYua3}pD z1X{7o91cM(B*yKjAJ*$m&Z&-y!O#Hc|8o(3r=79h|HpNi@3wmGeJ)9L!T9j=`a zqXrRp8Z1Vj70cWYcNV>TMgQ3J=+Ju7!<85{h@c#7MSc7xD#axtf@ tZ#A-KBv$-8N7n68jR@6XyU53KIL$`S|frviV)7L{{>(J7XAPL diff --git a/src/wroboarm_22/meshes/shoulderBase_link.stl b/src/wroboarm_22/meshes/shoulderBase_link.stl deleted file mode 100644 index bad98d04de53b49ce43712a08b7c6213f7d6b192..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 53584 zcmb`QdAJ=_neK~7`K2--A|9LC5PnR9A`K+qr{!UF*WxfsGEgUpB|hY%2<5eJkZ z0>U|f2)Q5vwvcl+Y9pPijX*n~v;znNQ9zWz+o0a{uG+uaZ`ImWKl)^}U)ue&eB#Fw zi&J97`}W9}9Pn&ZUH^b@U_ii(u65*H8SHD%LZeHV|o!l0k66-zE z$)7oP%VEX!d>`6=WM}P3zJt9^eeoKDScX!z-EtS{&pZ}8Qi;kI6 zX@!*VQaSPP7pCXuJ-PO9JAq22I{Uy4^Y^dzt^uw4>}}J^l05a$)@9#>*rN+pzH~qi zJc{dtB2D?k@EZ`QL~D!<&Os|mwf!oqsojCkAYd7?V6R1SfZfOoY zQaSPTto396w-cyDH}{8B-<RFXAZ7U~GiT=?a_sCyA|I`5l9;uwr3?4i`oIoY|*4ICjU-!jB2IRmal@qKnX+4}k zCHmv%ot$sC&#VD`jz=mdnpbKkP>Fu^Tc_ryt##Fa96Dxjl+h~6$ba^;uMQ6$?RXUT zvg>9TQW6R+P#KjzsMQs%5Xa6CrlPQO#?PN;zcf ztVX5EMz?+ZtnQXyJZ$3I8(lcQ?S>oW3ol!`_|lsfR_r@Juxb94D>r)s0+k|RE5*p@ ztp|L(yYZYq#2k2(!|kn>Zkf;h$>BwRG!m$k16w(=Y?VdB-J_qI+I5d|ppyOXSMHe4 zT5^6-k46HOB4HOfZaH$r?q>gXK+J*1fAm;;Z;mA&bYj>zY4_O)J)CIXdm zU@OPS*wlG@=D&UNQ!xh~k1PA?=TFL4Kl!SdqnSXZ9N0xYF1zE2{Q1uw8FS$AxU$#y z)j9cBZoQ;ek0t_@a$pxZe(-^fJBKgbIp)CQab@3n=z@I3<4^15Xd+N42X>KTY=!+h ze?4v0m;;Z;mA%E$7v|^QuzN2@6M;%Ouw#yFi*J0g^Qq^)9_Jt)k1KoEB^TxEZ&_ST zWQ_zW<-k^sk?X&+a4f)7cmDOk1PA2|G6Nax$QmiswitDP$>s? zFULD~>zsAjP{%zUSN6pR&d*PO?tOQ5XRgsXZkK&y4m=)L_Qp@0nUBm~ zQsihPP$>s?QK|>lz9ZlMO((@1cs#D`v5y^>zi`2ey?QhesFVX+IYx%wJa+%^zdSfM z=D_1|WiMI&(EQ+=UynJO2~^5~UDRWn$s0`Uc;lyI4m=)L_6ke(&Zn-jv{#QN0+n)L z#~eeut^DxBZnqy3bKvo~vcG-JF8Q=S-_z@lCIXdmU>EiH%|q*T*V7;=KYH)(jwie;=D_1|Wv}t;&GKs(Ozq8&CIXdmU@OPSl$Uou zp*ySlW@wl?rykg`0?x&_MZYNMF2X-XJ-g&@wo%L?rx_i{r+s5zs$07N3!zb_1 zS@gY%{lDKnC;!_@o5Z#nX(Ui761H+=WB0vqSZB9IuT8i|IZ(+S+vxcG?&ZEy^hYCs zN|CT*Jw_kB^Nh~s?QI8ka*|xLu(rF#{cwE`*eCv?>&Bxwe z|OGo|MmyH98Cl&<-jg-9F@(R{`SAli#hOkT-g`@b?f{G`#sRh(L|t94(uYw z!>6A>|fn%N^WZG;M{L z1CPg*ec6Xs$Twf@f?kd$0+n)LE62!`|5)R+?&`06Db7JW9#{6I8%)aQJiUL+(M+IH z4(wQu$$xruUiZ~GD-XNJUO^P@wo2d@wl?T z{>$a_oBw`)v9>o7sFVXcw$Qf3vkN?7h z#d-T!6M;%Ou!|hs9j~4^VOKE5;nn1S;jg zE^7X}^A_ZPoN-1s>;?%EKb0mbyE)}Ki6Dx+cdTjY^I_~kfvekyW9{c59jwS+?B4NjR3_Tor@cGbQ z?(w*?)w5Gh{#=oxkwB$L*kz6ha^Uf}vX@?dNWUJ+F_1u|9N0yFgqnA0D?A=o_Sd#O zD7JJvfl4{B3qm73jH}p#cs#D`uO2w7I<5v1sFVY{k|T~?JRX;P{rS-=RYItQQc;gS z5oT1EIf%;R%2pd{1{bAjB2dvEB{3FOh6$C-JswxK#)4Lin4^(ErAXK%F>v)kr5vm= zMLk{(z4vUdRP4}eRkJ&orCsC*?bK22l^vB6vbhJ{PM}gGY!Ua3J{RWSW4-kXkH?kG zou+mIm2zN5VoEPZ9J_ctF8R03Eg6d5sT8&$P#XKD^kj;T|VKsirGOS}G^1s($^dIYQ~mnmZ9% zA?8pkREdc#Zi=<-<_}B{`Nm^O!V^0eF5N2r{?=n&nqDQ`I@HqHH|$$5lj1*IoBGVRkytV-Ce~m9JgZdbr04tJCym!c{gF zA~DkKaYKx7=12IQ=Y_`^G18`l=7eY`WYbnvf-__hI^)pug0gu+FwKFdPWahtH3w&X zA~-vfttYF_Kjy*MAI$_RXs#xz1bZ)1`F;sc)}{5pQzv})qng7BRHAu8FwKESDkpUP z$$m*ShZCqobJdsTpxve799}m4loELA1TEc8pb{OF4dV)rR8CxU<(u;pclhFfKL6OM zFAeYe?O(;+hzB zus_pIpc2jBH>3m}shseApXw-a0+nd~z9G$lM=B?L*SVU*2~?u_dy_N=9;uvQqK zfl4$_v8MzcshnVSO^KbK*eGX(`|kHQiGML5nk)U3z$29tiuCfMD-GyDCs2uI$0E&v zM=B>)`po2f^ym*3&mmXNOPoL@nqzyK1CLZrXjK|~G;jiyXpSXm4qxGvgX0IQYf9ju zR1ox2JAq2HRy*#oRA&?(shpsn(i~2p63y8_O5l;o35`njud1bT0+ncHbDD$Wwp2RS zYGlX`%4IkMa6-rV!DE+Lii=7%NA0v!cr>+usoRA%&mTlEcpbA$RaaSbG;U15x-=VYY=2ef3vv%`qpUlHGd5qQD z#VOkx2Q4mQ94KWGhEOOj@vDLOGre_gUQIM7Y+vUO9?gwI-sf@;#YAcdz=XUA9EDrD)jk4 z!d0@Bqa2Bm(AW(lE_yT%T&3Stk79m=(Ox0&IN|w%-{!gJ@VLI4P$k^sM3|3ZCQ&NS z;e@O7JL^iC1CJB3`8~`2dhm9!=Ih+Fb=UX5rBaJ(2SL9pcCp`HC-6AY%a@7Hve#$6 zJ?8lRY5P@j^x}>xuJ+qQq|su(y@_yDb%*|dx9k~5`;$vQ)pd^(Vcv`?hwgG@SrbuJ z_4l$O5$CybNTv2EV)f&Oe2e?_2ss84u9B@tWz9qEY(#D49w)RjsT@Urgtiiq)d^S0 zR*tdh*J}((j5|^kC@om;(Zj$L;0ojS?wBH6j%aSf_Da?N%dj$sdz=V6Y^uj-Wp^-^$_ZETdwJwca>(O^ z*>Ptg0KJ-fELVj&AM2FnaE}vKr|F8Xe?{v$;VNsx8lio|fU9+uDQo@Rkeg(5BE5s zo$a6-&{j@VRn0Z`<96kEUe24MOw>G#jM!@$)%1sEs{LLYiSBU%I~|FG2&uvti=!mW zNBuYcEBeDd9@ocPm9QMTYeihm^H{%P_3<3;al&$_U*f-_R8F`mtXDB#u_ij<9w%%} z*K#=Fs<3Lu9F@DsakRU~iO|DSLRm(`{Ls1;{}uIcqN?g2eX2w#yUH0?(a;Kt7gtUj zm9=`f$BEwB-aFzHS&C9QQB^h7!^`f3AK|L?aH6Ves<|Ioe9rrksG7q)PWX9gGvO*7 zXM?hL7Ot`%9G-^Wl7svUG#|hb$9FreeZeC~lv^#Ydsf^_+{q97T-M-)1ojt$*{#bK7b%Iui zZ8f@5_)Da(%{*7n6jjR3n|r*3S$5<`SB<~__MqQzs!n9tj04`^Sz&C$u6vx2&2DrtN}32% zii91BvCD6HJzsLuVKE0Dk1Lyf_;v!7a$pz4!Wp;b_pJWOm_t`4x?|!h<>2=!;hs8C z%@Mh9-XN7`C^?9$Nc>*pfN+m!C$OV-=(#m-%YX6tlR8qdzYC!wry}utm2gj;P>%BG zJoNCiS0IkH?i=U45DeRLX&^9L2FC z7(?=~|1DcPkh+U3+iPAW*r$ZnKBa7SCes`qmwTS=Imj-R6Wk?Db2x!YG;bhE2|Q9c z!9DMkU}u|BQFC^qQvy$&pbgszRHE5iP6<3xInmr7>=ldP&X4ToQG%yVaEB%>l@q8$ zGp17lk5o=DLfZ*cqJ5rM$1WbJoM7~%Ii#YWz1^By7Z3H&v#zpfku--Bs6_DGK}z89 zxUxB4X(v#L;E9Wrz~gacb9XT%e17ouED_B!3XfDyRNk=_&)Gw^xL!GdN;I=MEfpTA zc!Qbj=03+$Cv*o(Z)Hn!IDtyEj%pk~sv{APR8H^~xHN~iuCFV!TT0+j4kvh0p`Ab_ znzyH=1m%^Aw;ai)ekp;cPVm;Lb^;YSbS^QN;4H%l-k#M?pi&OepW3pi(~UNche~>G8O-S-aW^ zRLX%ZVr2BBkDS=Ky4YbUJswv!Yj8V(N;$A&sjffam3f_?zkYH2TM|4TS2o9zb^?`h zV8>ETx%-1BcP`#H?!%QHk1N|}?MNemN;$A&j!rCF_`5ZE7;&;08L~O2|RVe#}$98R@B1@RH8Wsr#b9gw0zP@1n2N6fk!I4t{vxmelVePH4(P9 zmo1$V-nve3ENLfDDPMCBdVknabQw$K1jonrQlV0*INGHIV^k`;(ko{{N-%Tk1ZQgP z1S-+Y=9IuAl@rb5$_Z4WE9+Hd4&tF6I(w1LI8IAN-%4d?;pJ>j37_XqaMs^Wpi(}r zGExGMRCdL(jHPlykgw`(Jky1V4;E~Gq;VOSq-AvdnUdx)uYN;Gf zFk;fSasriTjw>mFM=B>cKDHC6L|3j@D&xvqx882$-(Xb;+ixxVKsj{uDW8sRBv6Ua z(XRaas0!gTRU=04eGt(+Yw<|sgxW2AJHE$~jY_s(O;kq-o;tzqaM~YEpc3s@Uez3U zq;i5*PjfhdN;KD^DS<~SCz|`i2~?svGe~pbk;)034Gtb9PM{La8HaLYLqEQMk9^`C zXX~CcWcY_xF8`09Ea_DY&>G8O-m9O08Y$Q-A61H+= zW4*TOy2sZy2%|mbz~gacbI#aKpi&O(NT}vr+6s@ym91lY z*&mGrD&@c~O0`|+i$_8p_jp{{oTIiAs1ylX#E3>>H_VSXcJX*z*__F?6R4B}I})0M z$`R)v9*;}D@(j6=Pzj|{4s7KJyR=1Hb=>1|Wpl38PM}gG?1Bg@T$eQwkH?j*vA{W8 zToVTpsFVY{$nl-f7g|r;<8ftcOmn`Q4K)#{6bZY?(R4IGr5u`@)MKPPeuUkcGW!v$ z{a2~d?@siO2JUe}w$>QF=Fv=`QY7qHkMj889*--Vb-tZIrAXK!`o|CVcwE_)qk+b5 zJmS;|RQeq|=Fl7z5uez?<8jHC9zQ&mtH=$}KN`5l3E8aqv8~D@PMtud-?1Z69u3^% zab>gSw-cxo2|Kn`dHisX$Ca&dT;7RmBv2_5c2RSVAMWwEvRU)n2~>)NUDiAvKiuPS zWowN|j~{gcm43%AO2zTRJswv!YkoU{N|CTd^p79z@wl>C^V8v){_(>-9#=MNzDm_hpi(64g5db!9*--#dNgPvP$?32k%Oawdpxde*7IMx1O$csrqzC{~^DIhd9T0u?#RwWPe- zCa#WNvKdzpgX`g?a-uTYD>^Clz_n?ofY7Q?ID&_FeUM2jf z#_@I8OXY;00aSB%sZc2gEfU9WrFA*7NX3zC*-PbwN;tSbyi}-^gBFQ%P;YOI?_$-N zm#+Ku+=9;A>@HB{nTagZ+b{KIM-irSqH?dOnXocBTa*9lbm z9lMf4*R`d`~D#xeK6O z)yjKo2NI|h30tM=zX{qs!LHoRVCTM_K&437ktpBm>>lMnMLzBV^xp(sCu|Qn)&rvd zUS|=eiuI66IoRb^shSB?ii8~r-lnU4hSKA4WwXEEPM}gG>`0XFp?8nRmCap;b^?_m zVHX5%f_9I`mCb#Tb^?_mVTT5>mhRwqnJh9_bxLJZg7rsbte4X%1RZDvkiqZ`^}Uuxh6{sG;Jb zB44>umm`tv8V$N$_7Y+%NB=k|0*@22DPcQ-ic-;o{o|l}Jg#i&q#VrzDn-JMM0p%^ zkH;k+ZPh;x)(O>v(T*K!UVagQdPwDQWvdO#?;A7{s1yl1=AZ{V?(w*?H5M4V{ckAL z2~_$WyQl|WL~xJCmF=TFE03IY0+oKpF55~gb*u*-k1Ly1qMbmc9M~fI$3gdaT-mHE z?F1@C!j43F9CVMzC0}K<$Kzm~P}!xTv=IH{pnE*7Y_(x}9IO+l^gFid(f=ZXdpxde zjS`L@%>*h%!j3r@yIuEqT-mHKBKm8)zLmiD$7J(0Fxj+QO5mvzUi0Q0PV*JDGzT6p ziEJMw)f`Ts62aHt(j0g^u5AB$T{Q=uI-xqT!Zj19MDwk^v{ZPca)K`arUafkq5fb^ ztd`0NRHFHkVVVPvR8H`H#gxEPCwxt;mdXiKqWMl_ngfqiPVn{0l)zIb{Af@ul@q8$ z^A*lC2Og=M;M<@nfu~ORaj;q{Cs2v@ub);4pWA$qPek*q#Uqsyd}}YQhZCqo`+8L^ z6&|Ua;9GlX4ku8FZeHQ=Naciog|AvFCs2u2OLP3F60|!itp>9Bu5DTmJaxj)uc|qm zKqcD0+*>8Ce*6CUPxALKmWr<`$5Qzh3(LK5_tXi#kvyOty;vep$!=~dJauBszP((n zhZCqo(+X*+@JQu^e@VHT!wFQPn_G9+nFr=CJ^1c%sTMwQV7~uqJ4ajlWw-1yx%g|@ zO6%gO6W^Hszw+14+4T(wRHC<-GbiRwYmP@MCl0#j*!;xbZ8so?6R1SLdxuZtS5IAG z0D(s;C%(Vl$@!$WtosH8D$&Qic0&I5DUZZAG*$b<$F9%8b#K@w|KvfJ4IuC+t`oC1 z*(2Y6t&84(KqdMuckSI!Dm+p-vElAB^7U8$`G6cwpb~x18T&T0E*`0zm^|f!`E@71 zeL(9vfl4$ZG#w>)q;ldd`|XooGG+4tIh;TxnvtL8@E+XjrGxW>XTPPg5~YN%QBG*y zT=3IuKk26RagHv{2S8uc3E*`v%<-)jKm7Tc$JFL zE}NcJ=>FeS%fs1{Y>sNOIS)z+JavMznw0R8FwaFdmkN(mPOuWCIh;Txnt78Fc%*WI z6}6o}C7O0i2|Q9c!P!|mfl739>w2GiD>RQ1Jc{cCvpFr56R1Qp(^A4~&Q+KQ&QVeV zk5o=@Mb=KB63z8hN^tfn6=#{UE9X9y8O7|B%I71qIn9BmPSA$!1S-+2F)4vZDkqxz z!{<3WA)@K0GzT83oM8W{L zni6>G1lQE<1S-*7Q>O$Tskka$_EI^)EJ$;BJy0nJ*9j?sM=B>OGpal<(KnWlp0j_x z=Q-Dm`!}6s`*Q&OGh})0{J^I9SFYSF5?d|ZGN1dC!=vp_CsYYMqMi8nD|gIiEjhn- z)+dz{sMsH$8)E; zRGa?jhbn>`RXTMHJ~0&plUA_<(0~bHGXwY{*_xV8IZ#X zRHA8-v>rZ6yf?SqaHD+TWlL*keTs!gwiEtjO|^BMKqZ>5xum7SBb5_;!6zl~)CrZ4 zr^2eGasrj;HLut>zx%1F18RQpf%EgzpSxhXRBCDct(|Otj;xx4=hLKGd8Lc;gO7Ro z-gbgmb>g7^xgejp?LEai&nlzc2~?sfZQ53h2C23<`ojF&8+NbEm6Y&V{%D*r_Z`&Kz}%aN;EB<=Acca+W4t6^O4z0D!rK!-p@{q zeeAgWg$rJs-cF!WKF$C1FLLG43ddM_+njClonDw7OU0;6bKnu}#2UZeEWdWa)B&T! z2~?t+N4uAO$?}Kh2jBd9ELC$o@F=bmD=gVNpSsG@0d3_3DsPdr=H6CLeEXVR@@ap* zXFv`oP9Oc>Tr8h4uziTL)uOiCk`-&++E4oUy*0J(3|Z9D$yD}<-Sj)2k}Vd z1fw#|;RGtt&25E8DkqpXX$~h)iKd@Yf;~&An6KeM4*z* z_w`Z&Pn}?mX(v#L=DaH<@JQtZXM-uh{;mkl+hw!2oDz8I1XmXA1S-+&k*5S6shnu8 zhZCqoGt<%>c%*WIc55e4iDm|;1Us8jaegJ6J1HrFr%rHg*G`~{wBIXAR#Dxll8P%N z*^GrW2c9~?bz3`uN;G3ECA{ohaDLrRpc2ifObL!&QgMDQn=_7-z*8rm&CXT#lll3I47zSu9A&P zk+36?z3)%YP2`J?h&k{$A)7OUb^?`hU>C$Xw|%60-6vLyIq-N~*{qfA1S;jg7BMn8 zv{U!#(8BKVxUyNn+X+;Pgk6+sr$bNd-uJn?Cfwt3WpnImCr~L8b|l7*{oW?sBd_Un z-Q#g(vsShfs1ymiAhuZbw284x&x|?ncwE`6G3^8@<-jh9oE&&Ou54DC$e z-`k{fO0TW(cwE^W?b-=c%7Gn;EcAJYKF8y6WwTbc6R4B}TSOeY9mXymk1Lxsrky~g z9N4i`L#y2OkUWK|^6GAAg|lxQUT33u9qpKN4^o8N+?7*~kwyZQB4HP$`us*q^Iw1c<1q&w<#3z( zc}&}v*jy`#$zk?VtHKI+|z3(P$?32L0qxp$2;df@`nlccwE`sX>2D@ zDH67bk+B`G8|tjP;%;5{cwE`s!E7f`DH3*3stxYEGT&mWQ)3Q19#=L`Dzp=*lmj~w zW4}G=uJOJ8J~!sT<8ftk&$FFCr5xA=@ug2cH*v`ikBB+&cwE`sS8pd!DF?QQk+GRK z?ACqxnJF;`9*--VCnMSkRLX%JiP2x5d1`mjvzNzlg~#K{=J|4akR!VPvB3**p5yVjvUz@@oj|1=*aflfQ73h-cT*o&9I89KZF;4vT1ZLaIa=p!I=l^0?@)A)`U66??+7;&s1yl1mTKr{#ryhV z4m=)LHamLl1S;jgE{Gq7{?@xD-Q#g(`(9r*)I^|CBk1Ly<^mYQ3B4HOq=<_apj>qH5X2-LgK&2emk%(_kx-ImHdpxde z_Ile1REmTh3BAFrdwcN)v(n>n$ydzUz%&x_rJrt|Ba(+-IBoLglt+tIYx$-TW{@r{ay|yP$>s?BsxXevN6Rv^~Hnp zBQN-C99Q&*e%ICZqEBYECpp|B+X=6E|EZTcfl9ysed36iJ1y1TYtG7_-g&e#+C|*{ zwgdB(&-h;L*$?-~rgddg!ZZi5TqRq%r!9JXKn^^0f;LQZsD^hP^{=rW^nqx#?swm| zU_cH$QaM4L(i~2p60K4xcS_)q$_ZLMCA=O(R~=dQ4JAwoJj&t3_ivcf(1T8(63vK7 zbKsH63FRBygHE6lT^WhxT>#A-=DBQW+5I(9bFlX&wvJ-aA0OGe8{^Xdw4v&e4ZRlL zZ1jilKe9{ZglyWaoj|2X*pZm>yBTM6Hd?SC9zXDST-mf+JAq0$up=?r%Q4{|k4rxK zBWom7LaC@nNsRT{s_Pz)E8BZ8Ya~!95_YUd_UG^}y`?kGh&k|hT-oYb*2JulK&2em zWsV7Q;PJS!eJzPO1`?>013TtW&AVY-#d_fJxUyNt+6h$3fgOp_zl3(WJ-qYGJswv! zt7|)fN|CT5F{PIyj$J$+mwY-(v=gjql(r-^2h~<_4x;k7vekyHqH)#^Bv2^_wn`OO zh6%k9(LEklw#GtvG|*ZykU*tK*kumAi7n>9<8ftcOjD2k(ODk)R<@5AMM{sg#Fb|d z!ThM^AQrS#vYBbI9_4unaaj|+Z-|r*1>?Eh>WC?K$d1+2@s- z6N|V~$*zp63PCGM#VQK@#y#kSukF>Ed#O;7ub5H4cxbB$)&Haa{ONE6J$y8nqcc~U zG%UOLiqfRv3zu#+UBAEen3uwTov3=Mgy@3!+duvhb3FR3L%UAMMm4d;O)*C|e<1wV z3HQ_q(FHO0J-dbSXW4fy8R|MA8`TS)$77E0UCZ!aC)`sfL>I&zm!1@J?7q%z6HdrR zb?)j}XuE85lbi1h&+j_no;o4AAp9!T3E8OZ_u}tTW2r*cA@|gY9vuiPRo+0{YxP@P zCEQ~X5&Aq3HcC29SPw3?@m3?;Qzw)ojNL%kXzw^- zBQdB(rl`-uya`ucPPnH|6m8Wb^1y2jcASunD$pTMoP$NFN}}qi68(CFwu(fUgQ`av zOE#*|3i0={bxXoMbwYGOggy`Dk8@D{QO1&uD)eUjJ@=Q6NPq(m>vQ?>=aQt%*o%wMj$EC{!V#amLmT zR(`z7DAcsYwgHn$8~%8=Iu#WoP<8ISJ0UIA+UQVgouSjxN}&pag7~9T67Bl#y+8Y` z^JAZxKT1Mo<*x5%t+juiea?O7R@MLSe_J*w-rBsX_Age|j?whB?_2)#$p^+qpZ&&) z>^<-Q=kZrBek9mCZ+U3^x*Pv>rAzEN_42(t?|3$-ww-_9-p^nCOeF63%xv=BZ}$+y zQjUGEKREl1O`i*d)w2GE-B0xqDV7MI!>XOB+HO@|wdd3Wd)NOqwy8|u2`zVoBHg(7 zbWaXXpz>|%R^?mk3H9Mup6hG5Cr~NJ@%7d6XV+#QeExqz?=nu^s_-bTC)V!%o4sHD z?dN-1?g><}s%rhY&EM)FENk#cLKv738VM+SJfhd zDz#~*Ug(a8wKjM{?dRMxqu+?sCGfO~v%c`a?5Cbw?8)H?RH9#X(x!b6?fL3O-5h=d z{n!{i?$3coaXn!(*h4&e=BH;5e)xfzRHN5EJG*(?CBZ)HzF(Z3_?>Ugy1k31O^|z- zKozTcX7M#I*tD-pR8{my)g(&o@C2WvvY!sXS3`hbK^pZp_4qov+sId^MeX^uc}XoU%Dz$z~4@?I;rL!GTV@ z>oCC{EP}H{m+&ff=V5|aQhCB6)hC%oJ3N6(w6(lG!!-!6vX+Na*f2pXsXW06u-kG^ zpb~A@-TL&}s0xo%o>0DgW+)PQ6<253MCv8N z*+43GYT4}hU4mFrQAx7vox0HuUzI1yIXr<%Ik>KLtKwQKRaKon($!M7(c!AyCGfNf zdSRGAm8uG-fiA&0K`Kws3xSw(NB_=`eKGf_Y-_{pA0K#ZCD~)y!vy=Ir@MrY>k0PC zVFDF7ZuqC8Jyltbu{=^S+lSjBg4TM1_1LY-S7JoCcRprSGgnn6*ekm^)K?IwXveWz z?uo`aZ;ZL`D^$MUx>d0zq+(vlZmf?+4m@q5JQF>EN;GS;TNR$93j2y|Ms}D$C4ybM zOW^TwWtV3O>s%_wU|d+aA5_1L3KP?$!0Vt}EQp?_WRbgbOCK%@+g$k0)ev)mDx&fl4{BMO2Ib zed(^r3A=Z1c#n@8^VQEw$^_T;*p8Z57^NJkh0){Vl8+NWnc&(^wGcZ-sjnv9(l%ku1ug(4s83k+O8ZMHcLVdJU(v97fzYOgjE<+ zsU4Zvzi53mw|PZ7g2%^|Z9SdO)MWxy>h(-i>o(?dn^$4XQTezrUwk^Oc9aQD`mr4~ zu`o?J!rVpWE$hMvicNxP3 zDn-H;QSUz9HBs+A-s9tvkKLzCsCKES7NXvLyvN6l`Rd)LOsJ>% z76@BiRqsBr9Z}`u%9fIQ&N6{Yk<89J+*;nRyvN5)`SR{lCam_LO4Vkf-hI5s$CYh8 zop+xyfl86E)wX)~@g5&H=Bsy~GQmz1tF4K8_wgPdmwfC#WkR(}MYRz1?&Cc^Zp_!W zU$qI1hg;`8`&Dd5RQb5F{q9rmS8W27KF8K@ly@IgDPP{Ns?pO&Z=QVrv@6Hj$vC|# zuD7|5uB!jM|FrW({Gf+GrAVAntLis5Z+bw)&zuo+;86~U(7yEDt=h2=s(K>j@B~jF zMeuoO`RJFQxPEfQ&2L-r*}Y1(KOt`~5~vgjTRC=&?tJ3X$t`F7^u&97T-n^W4HKvo z30uT_M?d;&hgZ(n`qq#GkB=*R&3y-1CQvB{wsNeEs_H+c_HW36$Hz_f-uyl15D`=< zMm2K?{_n)e&OrT1Am5FN6#$(QSpz?8L+X&|8qGbY=a$twPTDN&M zXI|m)ab?>~te*%M2~^5~tsMK;ZGFst==3Ycip9N?RM`5Qr(acd@#BX-DMD+|dpyz1 z@e{iieon+IdI%~}B%XMys%k1?bE*oDk1GN?61zYAuKAb#VQIrxB9(6k_n*TADn-H; zv19t;Q{FiL+%+$ldyjIUlFj|@Fo8;uutmIkdiU#2nZJMGS3(XvKCW!;cZUg7%7HE7 zw&@$+^-CL%egF4D4m>`tY`)VOCQvDdDf8X-s&cH51CNiJ@`Z1+l%q^og+Z0tk%Sh>J`CTUDMy(=mBu3z)w+%OgfU0uwA2~^5~t*WX;o4XU{E*>9O zHrK>q0+n)Li&)D~guO@h{N$e;|HbED9Ijneb@$?*oU=7PPizpj*1}&?h_Ia~{Pl)x zJJp2KayJKaS1RV1Y-?Z7(^~Io6Bawqt7bchB?6Uf)_k`rJZ-{yVWwUfCQymKV%x2= z8^8II9)doR%J-E&={MVfr%iAT?pEaqRH;q%Nxw0Is`m{$&r9PR?@UF^Prhq*?Y%GW zX$PJdwCp1fDiQ?qLFzXj2xhoOq;a5~UM>CpagFwvo+O&iamC_xi+5-?4-- z(C6HFhdX-RO@upo@9~6eMmF5h>uw_4(YFay`kZ@p^;LaG?>#=QK8F@jpU8YAQqd;a zjOH+bN|CSwkx!Q1ZJ0o%NZ66!r0+dGu5A7$V3#zJv50A6K@` zl6*og6Q~pkTREyJcf#J|OkPp_m1BF(8kHj zw_ort;Vim3EfJ`c16w)vuYb?JrGCc#0>XQg1C{LQ^}n$E#UqD9jxvEtk+7AcTHk!e z)swgE{Mv^1__(q!{@z=b&%5gJkfThXQY37pSX&$&x?%FG=PraCczj&hKlaGmm-AaG zMFN#_U@J#8QjS;KD0+{NOTN>$#rJW_gesJZc0jC-j-Gz?=>mnpLmatD_i4#c+U@q9AyHPB4JyK1GkR;z}oP zatsit6bU=FBdw^A1CNg@TPy9k+qa~4ln7MHfvp_dM@DSestq~t__!(GEVW~RunL1J zwIdU&>Z=X<3YCv5+j@5&<54D1rC!g({zV(}xvg`?BY1pV*)~h|F|W!5D&@ddUsa1X zcjwGqJU*^$oB8{g?PUU$a$tuX>$V2xtU)|Ju54Si`&j2ykwB#!*dfPMIoM0^__*ZD z`&E%pg;LQDh=r-`iF5WuR6ee3^&$IinLx#OKNF`s*nk1Jan7G zPgk6cE$JGC$H$eeIjt+)Fo8-rur(e#bmi0<4DG<<JZ*xN)~(7DsC$ltVp|pIOdrY{R?ZDSLR< zm#PZmESqY(Iq-CedL}m8;fdC~Vtusc6;JMz!)8f1A<4FO)Xx(e?ZDF}Y&7#3u342Q zP>JSQX1C>dr1FIIbUuqVb9e%kXdBJKiqbginktq0P1o>fyC?LGmRp_S*?pT(4zAA4 zsyu;8w5rYDG&FMHk;)TlQ*nKSSRzo#RPAI&SBMMRYQ3XfEt&|2xw;R#ftS!uoP2yd*X z+CyB~)~5PyqA`NR@+xRf0QK|scrA*1M!NQeH4#6rrkrHTgw-5WiLUpOiFO%XLFHl8 zWHYahm7|X931(>Mt40oA398|$6j$R+g&MWvuS#u#V2%w}g^GNo@rXMPwQK)4{;Jr! zM5q_?&M??lQi-5Py6rGeSQ9C3*l~`(Dpr>W_O5OYKZ2-Yj@TnzLaT@~E^FfWtMUZv zv75tJg-SW-kuIUyd8(q8>x_H+Re3@=I8(RRU}Jp*m2%J{p{o2;?Hl)gJ-pka_n?xU z-<9H>rY50hNO*dPK#Qm>hbpVKkwb5WVe>u~ZwxgFa+HYt*4EVi5>R>ORN@KVM6(>> z9X#b&%S6f%JXGa~{H9)IgsuqHUy;N2l_TnwXM!9hLUgFg;>S}Tl|Y>LiFYpj`RH5p zTh38mquNz@!eXyq`;qpq!?X!h`rPQf%Ga%G`|`oPmpptVSEAY@aWwqaPnS6F6VXFH z2#rS`!A8s51ihf#TRzqPbr{9PLk@^?JJdfPzv?O45yn}xjq>`V|Mp~0%kiWfnP|+b zMmt(Wo@1&?x%>JmdT0lIMX&b~xgDlja$}R{ZfBO{+C5>t-t)US?bf2=^ZpUkdalPH z#ucG_{UhiJR3bD^%*2K1UG`4Vm+V~`dFb7}-#KB!k0!SIYXABXd#?1nJzpZ0`rQ+< z>4jke741+@i-_--oM>;+d5@19^VPjuCVcN=D@A_?%9nSzGGXlqs#I+z_Agpr&FL#tKCW!*-Mn9w2~^5~t?`KOm@wveeB79?-gnD{ z&84tA$9B|2e8+^ji^|6(AG5tos6uuhY&B!Y)YjmfHHgQ@jrr<5u}r9^*|o8iW4CsO z4R!`RKCWyN=Dod4po;UVz8aKwABdDM?8o+*dtM@sA3;B3v`gjtsC@m1^+r#M8)jep zyj~ym-rgoyABkRK4K@kiSAJ}cuPRS4d%7(rR;(n>KH2n0moQJbl2JRmHj%mno-R?3 zd9&r7uy|o+B)aG7OkDM%Y*onqNTlJaJmL5Da#g6v#~Q3p`ub~b{vtv4p*J0w-Sv{s zhBw3bYlvo5`nH(AXp;T!_x;!S55ICS{ANx4*Hn53>!e+m&u_YO>)gi`QOeOI$nFW* ze6Ff4Z{)z^Rm#n;lynI^o{-JwBC655tqogtT|QAP|I0Sm`kX%O5_l9BLN=dA;^!^L z`6&k;ukwA^CFoI4$mVkq+ee!%{(J7+8rtDU4O=-F*)D-caUo>$c_dD;9KV}#;PEQo zhh4(=kEi)u#KQFVE&ho%w-k$!QVwi=?q_0?z~c$od>(VW#&VpKa^UeQ<)9b31RhVw z=5rCvHAriH?d=@(I#(<|OZ?1lj`_aB-`)3$m)5Yp&`sOf8@OVNtzhF2_pi&NO5o?QEKmPjp$F6%($brYlm2JOA7=9UXm_Vf* z*nwC-`=vL{Hy{4)viJD7viWtvVFHyRVT)LuUi9m4oB#bE-@oBKKCWzjwQ!g~rAXK! zu9?2+!87N-^_P<{+wu6gvia4*VFHzMV2jv2efufz*tq-l>q8DaKCW#2oh`qHSSC;@ zhvpl^s&cH51CNiJ^5x$hEE85?P^ETcVr|{}YC>P3@^NKbAJ)G$StL-U@yJBAXk$KM z%u)HcvTc^+-^?r%sFVX+<6$R#Td~YtJU*^$ey?+wK&2emBGyK>1}CgRJU*^$TbtpR zT!#r%%7Jaf>e|Tmk`?w6JU*^$+hh2>*8u{Ra$v`*Y=>Lc4(B~Su58UW?R-^r#p-*O zY>rOf@q?Q?1gaFN=l5P?thJZ9T{P5Aj{Gh_K83dl<&a9Bv%7|NGzc5>@Vl;3+1P}A z@K`zOxSp_H@A(y4A4@hW+2yKO+fw;mf;M&Afu~Kdj|~&3MAIW(!mkg%9?9J$@F=b) z*fE9)RHEsTF2Nj?%FldqcL_Xgg0(qJpb|}wh}f-P*wF7rg?HR--G?`W^c>&61%n-O zjP%6of9?PDMn!lV$P==83uc%=rAXK!s?n2H(KA+=_xQLmU;TDXnegw*V22!wDaS@^ zM~vm;l8?7*sv^NVI8+OSQwPHab1`M9z* z6M0*OdeK1EB(m^X6}%d1kpFvq$%tgk{ZN~H=_JM^(f Q&=Y=dFIR<%d~pr_A59&cvH$=8 diff --git a/src/wroboarm_22/meshes/wirstBase_link.stl b/src/wroboarm_22/meshes/wirstBase_link.stl deleted file mode 100644 index 0e2de13505b41fccf08796b9ec470ce260105d92..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12484 zcmb`NPsnan6~+&wK?D&96&4ZEeF++dbm{&6I4Pt_1`Vtx5)DF>Afl9lzVZ$n1Uaxt zh&9kxoJ2^F^?u)dCwI`G;8GwGcDn=@p~MU)LIYjT+WT4iS!eHaY>*(V@2vG(&tCig zIq#jO|L=cqdb+d2G~K*3O@Gb% zkY(bzJ4zHYec^-O9uh5T^XcDgKm7A=RgLRMOGNP??~K?!@Yk_MBdjKm0{!RLetYzh zuRbzp6+N}>K|t??JHI<1Q0=>Z@UXZ2cVGO>(Wh?x$n9l<9%v}>+5i6ZXnN>}0}Uk@ zwO&UawKkg8+Wpc97Ei4_#^3tw9CKkb=85nq(AL^LMzbgAsTx5*V?5?_0#TLTFOIo; zs6oO;_Iy0%rXB>NSjTwG(JFWlrG$;m`Qiu$!Kl*0d-s?Nt%~)bgxTA%hOQ_^)fW2da*b2l zub#2}YWL9(JmCA)WB+>p7B**oeSVJTL&7~hA?stV5d>EeHDd10h_W*v%4Ur3AF#QC zN3AOAmGD*cP8wz942ZTqX02)jXFh1oc#p<8mzEJMdg;M?YoJfXHHlP zx3SI_2}acxw(}zq7UiBA<$0+W`_&?W5kwR<7U$IwXJRJgdS%6#hyt|&w)!PT`+Fp8~;y(HCv_QHcGCCqMn$r|BNwT`wYCIagYdt%iHf_vAn zjvyEXnmc$;(1R!?xCgHji~`Md17g~h8`C}9ul&3#J7-#tv0wEBW{DECc{;BXh_Y54 z+bS4qgh%t5?azlAN<3N7TOZ zDADs<%{vpduPzof!oya9Fx#I;Uumn9h$zew?n+&&!lQXja}fFIP?vqLkp?)oUohDA4Tnp2)MW zyg`7l`q~@hY?j3PpwFecqF~3W&1247C2zdrpmIN{`&Q92Cv**FjXA-2Y{cMRQuDfp z8YHZ*26vx1!6-b3c7MN84{RlDY}y-S>Rsjn!6?}1!+8Hl1U+-YX3XFguDM_{3O3h@ zkH>-E8L+q01DizI^QBdZV5{Z?>+3bJFV*{1?1@FAogeL6hI(Lg9+&4bcW13CxipHI zVi!$>R?G1Kv0Mi|h*E;%-&d{#qiU<#+)b_GtVYy~@N>7ZCzWZAlPZ z&Ao=s5*`1v?@1-J;wxC(y$2EK!0{)WB-) zTLpsaJQMOppTnaydBTNr7W~>o}Mj;x1N98teFWdY*JJibe@+Rc(BJ4N56}=dQdhDKnp61&N?6~!< z5+21~A8C{sF1Jb7n5LI}w)cd3%B?1~s?xSIL>)6C>ZqgXJ>uhG#NFOk>e0%z4?Duw zHriXqfIW?IO06my+IA%@+IOG6awRmXKKGu^tx}H?Rd1^rrB&+Tyh4;_TGJ@=wdC~? zOd4e-=3Fhxo_F&q`bs>FsN*!&2tuQ*KI~UP+<)otjRz0E`tdbW9#FT>w_N63)|L;zbC8{jDiMj5Eq-jKYHcrtDpa#&nv#s zAusJhw70uVU_Ik*s6=U1BktSWcKcn2f82JLYbZe*8rc1K-^~O)nin>oqmHwut%ifu z;(G}_8dWQAZ+D5XK8Y_AO7l51zPWqFG;Y6g<*Mc?ttvF@;FpO^AaDI;6l0L|NL<_1 zzB*_w)`6&^-M#^20zF!P8IAYl(!xgE+TwTfy-@mY|KwN z=JaS(siVCQX2QnV-xQT7dX0E^gZ0O`s|0P0OFa_Tum;grz6O<`&GF#B zfXD=Tlb#bX)S4kYH4)W8p^Ty<7M8L}Q$I8eG+TVj>s?4gGf+nV^T` zK|MZ49XIs+h+H5TRqODRs3)u?JfniBdO@U94Rr)TyN*YEd(DLPD9_qN^Eq0TPG|IJ z5VT7j3pW7E8+V38^EouqEh7<(Vja9$W&$m#chN-iIV93;$y-8#Q5+BcN|p)qXuXRj zn$Mwe(0iiyC<#VE1LM!%CNe<}$C)&DqG|f4-E&{H`|dP7zrmWr*GzmPp^dL~R*!$V zE8k9(P|t`c-}>ILJ1G92rjKoupp7W2$90N^66zTdMFTaUWz+O)`#RTh(JoQ#`^+>c zQNP3ax0g(`FP=`E6pbhCdz|KKQAYb$wo->_1d%;G5q))9`s(GK60{Lzy&zwTEIJ7F zjEJIPHJtjG-+ybT1Z_lNop3JrED1tABO+S(!WOC9@|SI}^x=5^1AC>pi$ zQ=3<;!wJ%*j`ABq%q#Sj6SaR9iK04NQi67g^0`p!P(r`&W}^KT5;M^>p0IDc znyW<_?c*Nv3bWmb?CFW&P|t`c8dw`Xf|qY`owIj6 WFQRNTV~>g5=VUTMJ=9a8XuJ)<^e)~2 diff --git a/src/wroboarm_22/meshes/wrist_link.stl b/src/wroboarm_22/meshes/wrist_link.stl deleted file mode 100644 index 0e6b6ab511e886d43f894b64b5e3ff6133b1c466..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 50884 zcmb__4Xm|kb=6HNkQi#Aqomei0cSp_MW% z^(7<62lg39lnlMrTSaf7W{fk==2FA4^s`X3(W*UG$qK_BqR`tt=A-)INQX71jJx(k z^S{N~?S5c%3#Itg`%Ol9lOesc!wjRM=cPGqm3l6XhdEZZzp7S^49(4oM)uMuk1T(# z_G4#OGGH?YuVxfV5tzZn`0}-*qo2g<#^pm#{KVOfge+U0RTeV=6$LRQ3 zt-X>_s2{ofnX}*h(pzeMO&RG?>|%WWowuAl1CH z8HrNQR~YGe&h-b5U;nB*-SdvL-KrUb`|Z7l`vGsG)br9=)o=@%A-&^GjbbEfKIb=1 zaXR0J)A<_Jwd?QIlFGYztELQj7mP`sPc)KYRJ=Fr3=>A8VDrSW9)GSd_^w{N8Kd?` zj_#r#%>dK8C`W`R&WeUTK<{Fw-dX#w#*}dvgL_5*5&OIvzphZ#nZq5hS| zmv7>9#_PtZ)D^#XxLxdzHC7XbcQubqv19L=G14>BbA+oIg^WFM#)wmfNVbTtU7RH| zMtYJ#mf0NLvF9^Jqv9l*X{0CPZjWyEBTi>)RiCD<%C;vXZU(bfB_mPpHCwu>!B*^& zA)7a~86!Pvm9we(uw>w!_9R0iQta(kC5o~AS}@v^49)DiMl%vMUy0Af$;{jSyZG!( z#$GSm{#oy{RTGBM{Ar|r)_cXkxx=&YU3CKxk|@83EHvL+Fxs=h*pu<>`~KoL|Gm@y z^za|Q{(nC8-w=1P;~evS?{;L|b@P+|`iD-x@|CX?!yam+?cMb-!zgOlCgX!Q&)#EHi@FFZ{THH=c9`ZU;P09mM^e}hepM{d6GY4>0M`M3X#(l9FH()Q_dm|+w(Y?CqW zCF#kyvUziwWz-6zP@?En_(0+Y_lH^b3QITANJs9qiADp z`ZIuShEde8O^u)8y1MkbvM1xx#u}?n5DqhpqK0iU9)A<7{nD%5o{US|x3j|xqlU5K zeeOox0G@rDG%nJUaYL`p^KFJ&cozLA#$DGmR;6K7#-*(>tUTXl7)1@+?D+?;Y0fXx zlW}R|#dTF0+YFD1bhO>)|?NiN+(Bthk zK2KD8YnP$@&;RQ~`;WcjEj!v6k>26P&-&6cXZ+2l-oM9dx72VfGK`{)mNBDN7{iWp z<5r^H^r_G9KmT37=+n9P#A&OvGZZQrf8pOgy8rQ?I9bt1hEdt4Wk1BIJxUs7yR}P( zJ<*S1yz!s?POaO+45Na*GK1a$h(b^I>rSZmd=laXN*ZO!Zo z!#e{}JTKT6+HUPq!=5<&c{fjB!NiE^gWcCIWL*;}pM>c@7^?P1(x zD7#krkqo2MLaz2Y2d6WbD=`^b$157iFp3&p$IG5$mDIjV6f?-{$}_uU*fVD^dpBpW zPZ^`g_KI0*W#HkS;0h)M>=t=95khEZf=p8CX@&WAljC4>7R*T7OE8Ag%q zQC~9bAu1W%vAG5gGmIkJv$7yAa~PVEB|1&$Pqugo#RqQNdoxLCs)|kLJ8=w{|&J_AqWTv?{OYxlz%o z_0xbERV~pxdj^@!D;io?3x-zA6%3=;Dv!vr=k^el46Wl8jbs>=|xwwAojh(8kn#4WEe#@-mg(#w#pu&lA+yhrRT{oifqs3(a~Rh`|k3VmpFeo925qmgk+EB0 z7{y2*d*jnj{?eD;D2*E*{KnIZ>pxo>_GDbzUipK@7Q-lN{G%Ux^2uku?iZ!;nO}YU z>94>4)1_fg#-;5QGiZ?U*%gLS)cD2^{q~Npfk8A`>B+dXy^aqvjAA7Afh`^w94GcZ zJsFqwbk4UJMlllSf+Ig@ya2Puc~4KqrR_B~FgV|945Ju{Yl>@YV0=ARAy;F1GA?be z{G+2+VkL6j{=OB4QH+GlyLVXEWI*HG40|%J^mtFy3_|1Ftx5*^Q7E-`KlTH;ap9h$ zhvmt*w7tjlSgkUQq6X$;Kh6hc@WOL$PsXK<6|?8+A2hZYMo|OnYCo^9u00u- zHdcO}^MeLf`zpgIY9KfEV}2n1r8CN&j7uAR*mLy{8e0sbsDVD5k9m%9y5x#aPsXK< zooLV1KWJ<*jAA6r#re2jVZJY!Bk9Sww6Uh@`E$@9!+WA*C5n--rq0KG7psu#w{~iK zl0lnKM_8r!RE?`0E4^|gV{u`#)6^Vo`p7Art{;HIg*}? zOIsry42;!+VH6{248_n47Q>#5OIs`E3WibC(7F_kvYRCzOO70 zLm73Mo{URd8GHr9C`M8?W8OI*+8Ij2o{URdJCQWD7)DV;yOK1J8{FYa!=8*wTRW;W zINxgwqo|?XRT^Bk%#rkDT-rDpj)ol3`N7j*!7z%EVBb3Ah|Uk5IK{9h<4R9YsT^IN zQEpW-bPn#-TAqXI2k%zyxlYLQj7yt)6<7Z-gF0*7kBXHjYH+V&CiI;1&QJ_{l0ln$ zE?56yhEdeup358=7`$6CN79pVX=CMAjtmT*1ZxbV7>Q>Gb7Wuu%^O)|lsy@jHu_LG za+qNhHFyRx69xvxiFZ+FZFw>-ZOldG$YF+2)WBR+jtmUU_bGEEJsFp_Zsgi`$?%@& zSczgJ-bt7vg9dLg-rMa-25mpF_W5z@y*(L5QNzy+Bg1EuJsCIj@XYzrCp`D`KR)Am zm$yG~kDouVc5dAI`@iS*li&O&-*o=Aul)A0`k`}>jQ{d&f9&$l{NT&3rzaV-KlbjY zoWJ3_e{_f6y@K&;V7zRFVH6|jln~>uz47Un5B&7|O2eLvOZ#hn@8ixNdL}=oei<}g z4aWT|45O$q-b;P}j9>b|lP+)hjn9^bJsFqwBme!^_IRmP4}$RrRv1Q6L+6JWPyLP0 zUOe=HC!MAz%wlQSlW}QdwVYwqfWcMrQZPQV!Z3;&IzPntz6b6( z{}0c2UTN5qacLhNedOLd-~BZF{61)W2N=J)!Z3;&er7m2`d+pQEB%vV*pqRkcRcok zxq%$1RwaYEL6rKzJzxD`ZXie8kMd+(+RTk{KA0OGU7a{5iPC)Nd5|;6+(3?aKFX5} z+RTk%U2&B#H;^L>hEdee`GJ0LB{DaVBgL>MF<|KYV2&&pMp0wDm+1UpjugY5j7wW9U#((pAV(Gqqp0Cq z)X;OTbmYiodNM9;W$<~QAJ>s13x-jQq-+L5=g0NCaeAgFiC1%}R#>&TG>!zf1b zt#)8AH+Tz3PsXLK9TgfnKdvK377U{pNqeOj%njs7G3?2>wD|;p)enZwj}zp`f?*Uj zcpn;`KXiVaBS(s1PsWuV&q1|{xxqVD#!8g>u}4OW!Q9{-D?Q1ejgjVg4hH9gx#7{( z$$6eAM$)M*26KaVtn?&-GVL&W{V;vC@-qX=CN{ex>|i zZt#vZXBfrzb-xmWxxpJ#dNM9;_JOVJ^JA4^6eH<22!_s&OWv{4lW}QtE;uK{d@wh7 z$C@*Y;``W@&N(LogR{pwR(dinZLTS-e(k%=4c@Wl45Roy*A&-7pC6aJW2GnK(jIby zpI_?;|ClD4vTuE8?!Bp{OH%N zXe7fZvYn4h4SR@6#*;qutn(M$|L?Kd=lw{AQDi$GmkfJ|O2)-+e&_kef8w4Mjbs=_ zw)1hRVGmKs_+P(%=lR9|e)5V&GK?bI`MA`uhp1#+-1*&@i{W2?PIE9BMnykXvR17+ zu6`(P=fXrJ=R3!muaf($@T6!7z#pt?3npJsFp_ z*73=5tde0A8OqHShCLaVw({``hEZf_k6B^ZlW}QlU%7%|6dBqpR~U)Xo>))C+YEac zHyJt&Ry2}f6xqlPea|D6+BM^f|*^!yclNfiqLP7}Kf#H!lIO`Vifrs-H783Adx%N~_O270I4c^- zFp6yKu62`IYS=?mGO!1q;KW(cNQO~lKXJ|4dBd3XHS>D!+6*6ZnET%%|^gAX$r zMeW#2o`3Uo-}BE!FcfIo&W9$r@!)^KVKU5 zWL(-l;i$3AXcRQs2IJA2H-GDa>;LdWf4wy9$+)zAQd47_(I{xN4aOI5e)8G7>rcP; z@0Nx=8JBk6WVRWNf=1iW7{5QrIkzX{%I0(Q3Hx!7F`$M>!9YJQ+z)7!C*#sa|M+|^ zjV(r_hOuhKW1No*&xcVNmp0~!&*!DF&1e)f+D6YG;kvr?y0RzZ(#Cq@^Lc4(Ga3br zwxRJL^W)O_VNb@TjlALWd1-7j8U>BEq48ek`K9yRo{UQy`OoL`9S8>)je|=aBFO6+RqoC0?G@gGG`|hRpU3)SvZS28(J}-@JMx&t7HZ&f%52wMU zPXl{0Zt2DI`8LDP=ghRh9&Thue^?sl>B+dES9gYOhFZ91q_)wIhi}tZU8E=DmR@{b zvdz#)mqy#1k87Iq(y%Av($-q2erz)ug?_XRjkjLY+P!2y?8&&awWiNOIKXHWBDD?1 z`>!bnOT(UwOIx{F8rzIUL8EPGJa|oeNom-VacOIhDUEGLqoC0?G#iw`Do!_GDby$NmiYAY(uck%FPK zw)z2$@?>1v=pUcxs~=xx&v`m87>ydnsu_=QK6q#FSd}N^(#AaTiM}+p8I6KQ+Zd}y zxUP8jDGhrvE^VwgKGB!PHltC{Xd4<2GCz2SD-C-xE^XuupXf_to6#s}v<;2-GS7Jz zEe(4zE^XvLpXh5Z*=95f8f`=4P28_|r>_0Vo{UQy`xu|-OJkeSC}^||jptv}vw`=- zij{F`W2fd5z4pW{Mx&t7HZ=atZF*v<^TVEuTYB+Czs>OTIWw(oXx!L*Dl#hcb|6Hh zDaIPU=Y{hQw!axj+pS$P+LJBGNC!3Cs?fNiRnn`cJAY$r*(!ZMs?I*Im`R@&t;*ge zBUi~-k8Bc)J@@K6I9C2H8QI!>>gm|rt*h4;Hp3k}TR@EvfVFdxHjDq(kP7mW7I z7?_*!cd3(BC8JSbcb~R2YQ3sYWs9-0N-|S5AKn=@vbOUXElGyPYDFU%jRLz{xadcF zfJ%nuW^es`W~;qpB?`7OcqOAU zCp0(JDvaSqezXU1lYw#To8=;Fhge`V3O2@Y7?DLk+B0Kdr28&9)ksF8z{X1Ko8_Ew z7ssP+0N8_v-Y z4z7^lcPx{2m5fG>dMo|tdu0j(uju-46VK500R>yRSsL36 zqZr9HHO6Xh6Hms4tt=>wZH7^dWSbgeeYlAy^@ z2N^~&l5J{?_2DL-j0?MWjDrlL7|Av@#%ga9PsSbf>i4zV47L3%T3d`)bbYvqC*#7_ z=#FKGhBcr(5OJkd16eHQD#`tN} z#FKFc``8)>8HG}$W{lO|CZ3E78$ItEz&67uMzYO*jMd&Io{S3{GuZd5ZH7^dWSbge zeYlAyQJkO z^-6ZGk|_hDSkG!g@gB5K?Zd4?+-9IvJfkYlryAK0qtvG}XYG`sxI3cM!n(;g(&1Jm z19QU`T`}iIgyv{jn5YL#ZQ?60m>$ErVnB~O z+|{ir6!knJY}KT42{Q!PCiS9WLAK}MkzsTt$xoSuwJ8?Vmu zZH7^dWSjjMZyD*yxU?~YwXYmz7{y4o$(U5rZBNFftzDw>e4AkuHEdJk+p~^vdonI< z?JFc4U>G%w2=}YuuUb7W>me)FjrzMNW`tgyINJ=hoi*s(+G33N_Vi?2+8W*38MYZl zF_LZee0-WnPsXK<7uQv3Y%`2vB-_*&pNi6xacLu?xY|o&n_(0q*`~($beEotEBn|Q z2N{J@q-Kmysp-kMwDGDvn627o7{y4o$@pN_Z*Nb=rHvV^v*a+tC~DXyV^W8{JsFoa zR%L%OvCS}w8n&r1-V@W4acK`H(U4Kw45Nmz;^!#Cf7_>;8KF13GccBG6RCxD*OJEG zc|P7UQeBL?tJ5B9a^yXc9<9;+z#evI+OCnqo=i2eRjzDAhIWaSe%M1)GF-E0sgVq$ z$kxt)-p^ZQ4^hc*&7#8$qsYdb^cgknxjjTB!!?VR8p$wPIu6ry4@bu^Jghsa4$JRx~`fM7atSZD-nYKJ1w@ zh#cl;-l}96C5;-9RgE62WVpW5VTMuE@JKHi-ergyYVRB!(H?d?;^+OaXU8Ahq+Jg-(}Fn73Q=ww*YNQP1BxhfUT*OhjL z>Mh2F)!55c-mGZY!??*%24BH2ifr$8%lXjmQ!P;zxmA6Ko37pLM>3R;>#eF-Y>83X zr)8@$i?pt)Ra$TBGg!ICxXI8uUTKwMkzo{V<;@Dio;gGLcm=~KvOVg{p4&rIGPGl? zXe7fZvOPCd!R(Y3%v6u;T-C*DA9SYTTmR>(OtT*ttdgc$lkH(#GiYn1gQ2==6NXXL za7C9vBkIGoC*#uA+(=`KVH7o7(PhwJojcWjjkxtFp1G z@3kl6()OM|v?}WLO&CT|W32T;4c1{*-NE)`T-us*^<#@+6g9?LFVs-2Vpj2JPsXLK z43% zg9aJi6CEp2)EH~MP=l*bwI4BEPZ-&d6*Pr1^)w>ws%s4>)fISPhqO|~Z)p@*~9 ztzsT#tVBgWc4N<3k2O8XpskS(2KSRW!zjM5F%&~HSPXkIE^V!tD;P#mL+eTmu0+;j zO;5(9t(6}P?(cJkQG8$dAqH~;I;ZK$xU`kQS1^oXBxN&x@5UKqZeYAh!=8*wTlFgJLcNl!9p ziA}X8J656?NvDJus#RPX_9TNgDm|Q|N&*q@nXi=p#_we&hJZC4N(R*7mAFBnEqL#G5Zm>;TD zTnu|ME^XH}8Cs=U#S4Z})X*uRJXfva$|!p>E^SwI8Cs=U#S4Z})X@2%o#F1GRHS>@%%uo$xGELK1ol;4LzKLIzL#ec)?IVSnJ;X*bNNU z@n(*sC*#uANQ1%E&e3I#%o#@UeT}*ps#RPJdonI$ zX=^6}gY&^U-prAVl_uM7Yw5`hWwOD4Am+w26r)fGA?bb7~V_3;3{DqZ`Hc@-JlpoQG+`x z*L9yCtW{hZ_GDbzx;ZI7RI7NwFp3(wUx}ew#g$R^WL(NhVoAt_7Ihf{zlzGBN;}K?Yq{pRrU~-jQ&R5LL(VQk*z&=r62YXm5lXo z>SZk2M$z_NYuOKb=8W}kPG&6HM$y*ExnFA7GiTtNXk7zhI)lkDifo7)7@4TFbGrhp1!>RS{H2c#_i8`(Ug z)GF2yK2L`9urnND7)7?maD`z{^n+D_J#JSpG`hvmT3BJ&lW}Ql{;yydMTW9qg<(&| zrLC2ZQ*Az0$uNoxW%CNdo{URd8GHr9C^EFitT61!xU{veT){Ak4DFRGj6`Wq^c|(D z>@LU3u^2ZQ+O=0Sl3^6th<%?kVVdXm5S0wrXReHQkWnc0Tz9znoTF9ckw!Dnr@brV zO*N8X6xo<3ekQZhb9;zN21dOr<4rY^VHDX|Z@R32e8@YiTng8q0^w3U*zVD9TLC#y{Skg<(&|rLC3Eoo;qRPKHrrC^uIa_GDbz%Ev1hMv#eZAPP@(Ka+DRnpp%acN^6_q~0a(I{xN4UI{)xAtUQ+E~Y3gKnGA zC}^||jY-wI_GDbzSjS!QWSh|_XtWKDN%g(m{e(QPsT01xFK&dGzX>8Hd-~QHtqTFXA5=nriNBYwQ8HuDD0c>jcrDw zpwTuoCe_&6lW}QlM=gzQMx&t7HZ;D>dit(I-=2(1TX(I}*k&{e8f}*bPMn){`wLIT zmCZYxG!8HZ)DWo|U(CM?K=txuT-xY4&-2pQW;ALTt7c68T0zIkxU?~YyqA>5HltC{ zXd7cS`Kt@<$+)z!5_!KWjcrDwpwTuoCVxGmJsFoaGK%-a(%5D+3L0%gZ?aBKvV)9{1yr7cc}9(Y>2IPAMx$VNYZv{H##yv#PrF;YV6R6 zTTutt<7M^Rg)UAW?xq?Y3vnAY^n94jEsa`z(qL6!uice( zm1{Q{8ikYPDoIA8pwTOT(JIYawM27XwpPzdtJ;IO$eatO+GeQjtg`9W7GtdTHt}R! z*c#m(TeZzFiji!SF;;tTqaXLZ{l_n#_4R-I;^^pW-@`Zvp{lBF@1Ar0f#cV|>ds^MXN>d& zI~lv9qr2aIdim;)ek*42_q-<=Veh_h_iK+|cl~|RNJe@#7|{6mJ-=}AT|e}CXgqQ= z8Da0pK|&Q_x}JiK5}a^!ruMJ<Yf_E?=w z`cVwEy*$BA#yB77%h9uv5w_=C8k&z{Xb#G=!GMNV2^jz4S~9}++LcB!w3f=V!GMNV zJ2W1=Eg4}u2c?k=AGLgVSq!D0m4JA*Wmq1-;ifQI%f%-~0ECL`<}=DPQ> LDI+}_3~2mc!n>=> diff --git a/src/wroboarm_22/package.xml b/src/wroboarm_22/package.xml deleted file mode 100644 index 2ca5eaf6..00000000 --- a/src/wroboarm_22/package.xml +++ /dev/null @@ -1,36 +0,0 @@ - - - wroboarm_22 - 0.3.0 - - An automatically generated package with all the configuration and launch files for using the wroboarm_22 with the MoveIt Motion Planning Framework - - Nicholas Underwood - Nicholas Underwood - - BSD - - http://moveit.ros.org/ - https://github.com/ros-planning/moveit/issues - https://github.com/ros-planning/moveit - - catkin - - moveit_ros_move_group - moveit_fake_controller_manager - moveit_kinematics - moveit_planners_ompl - moveit_ros_visualization - moveit_setup_assistant - moveit_simple_controller_manager - joint_state_publisher - joint_state_publisher_gui - robot_state_publisher - rviz - tf2_ros - xacro - - - - - diff --git a/src/wroboarm_22/urdf/wroboarm_22.csv b/src/wroboarm_22/urdf/wroboarm_22.csv deleted file mode 100644 index 9bb21378..00000000 --- a/src/wroboarm_22/urdf/wroboarm_22.csv +++ /dev/null @@ -1,8 +0,0 @@ -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,1.03582841131364E-18,0.015606490089144,1.93574980271696E-18,0,0,0,0.93972387307473,0.00251429022255044,8.65861551705636E-21,-7.37485241366082E-20,0.0044229329573873,2.27711298016934E-20,0.0021336882069818,0,0,0,0,0,0,package://wroboarm_22/meshes/base_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/base_link.stl,,base-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, -shoulderBase_link,-0.0122586821821901,0.128577249577976,-0.00370544350042927,0,0,0,0.996366805002727,0.00652370094208947,0.0010646616036529,0.000283127005277364,0.0050231810993567,6.82113719161566E-05,0.0086334538259584,0,0,0,0,0,0,package://wroboarm_22/meshes/shoulderBase_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/shoulderBase_link.stl,,Shoulder-1,Origin_turntable,Axis_turntable,turntable,continuous,0,0,0.035865,1.5708,0,-0.25129,base_link,0,1,0,,,,,,,,,,,, -upperArm_link,0.0143973999054565,-3.20061625687929E-05,0.279348384794928,0,0,0,0.985210343915811,0.0237982224738339,-8.87977733299251E-07,-0.00388532856230119,0.0293594722597602,-7.12944369971275E-06,0.00625034839320104,0,0,0,0,0,0,package://wroboarm_22/meshes/upperArm_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/upperArm_link.stl,,UpperArm-1,Origin_shoulder,Axis_shoulder,shoulder,continuous,0,0.18098,0.043071,-1.1021,0,0,shoulderBase_link,1,0,0,,,,,,,,,,,, -forarm_link,1.84574577843932E-15,0.0550154986611603,0.120152803034247,0,0,0,0.517796101730459,0.00404850874710771,2.11419423634673E-18,-1.54871504075976E-17,0.00375548329392274,-0.000377385363706529,0.000788327838226562,0,0,0,0,0,0,package://wroboarm_22/meshes/forarm_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/forarm_link.stl,,Forarm-1,Origin_elbow,Axis_elbow,elbow,continuous,0,0,0.46634,2.4936,0,0,upperArm_link,1,0,0,,,,,,,,,,,, -wirstBase_link,-1.94289029309402E-16,-1.66533453693773E-15,0.0987034845564234,0,0,0,0.301763082175337,0.00210344289702837,-2.71050543121376E-19,-2.24971950790742E-18,0.00305016250706558,1.85669622038143E-18,0.00107609106501786,0,0,0,0,0,0,package://wroboarm_22/meshes/wirstBase_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/wirstBase_link.stl,,WristStructure-1,Origin_forearm_roll,Axis_forearm_roll,forearm_roll,continuous,0,0.04445,0.2285,0,0,0,forarm_link,0,0,1,,,,,,,,,,,, -wrist_link,4.30211422042248E-16,-2.77555756156289E-17,0,0,0,0,0.447707117943176,0.000367702266904795,1.79994501291539E-19,-7.45388993583784E-19,0.000843427086265753,-1.35525271560688E-20,0.00084474612356066,0,0,0,0,0,0,package://wroboarm_22/meshes/wrist_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/wrist_link.stl,,Wrist-1,Origin_wrist_pitch,Axis_wrist_pitch,wrist_pitch,continuous,0,0,0.23716,-1.333,0,0,wirstBase_link,1,0,0,,,,,,,,,,,, -manipulator_link,-0.000730323740460503,-0.000899365669252,0.0490560099953423,0,0,0,0.397420225554811,0.00159684305263878,-3.07243227891656E-06,2.53235579936151E-05,0.0016343224414688,5.00292290874635E-05,0.000256322563994287,0,0,0,0,0,0,package://wroboarm_22/meshes/manipulator_link.stl,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://wroboarm_22/meshes/manipulator_link.stl,,Manipulator-1,Origin_wrist_roll,Axis_wrist_roll,wrist_roll,continuous,0,0,0,0,0,0.096862,wrist_link,0,0,1,,,,,,,,,,,, diff --git a/src/wroboarm_22/urdf/wroboarm_22.urdf b/src/wroboarm_22/urdf/wroboarm_22.urdf deleted file mode 100644 index 79bbe3ca..00000000 --- a/src/wroboarm_22/urdf/wroboarm_22.urdf +++ /dev/null @@ -1,281 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - hardware_interface/EffortJointInterface - - - hardware_interface/EffortJointInterface - 1 - - - - - / - - - \ No newline at end of file diff --git a/src/wroboarm_23/config/ros_controllers.yaml b/src/wroboarm_23/config/ros_controllers.yaml index e69de29b..a79ae41f 100644 --- a/src/wroboarm_23/config/ros_controllers.yaml +++ b/src/wroboarm_23/config/ros_controllers.yaml @@ -0,0 +1,12 @@ +controller_list: + - name: arm_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: True + joints: + - turntable_joint + - shoulder_joint + - elbowPitch_joint + - elbowRoll_joint + - wristPitch_joint + - wristRoll_link \ No newline at end of file diff --git a/src/wroboarm_23/launch/demo_test.launch b/src/wroboarm_23/launch/demo_test.launch index bfafe199..8c258868 100644 --- a/src/wroboarm_23/launch/demo_test.launch +++ b/src/wroboarm_23/launch/demo_test.launch @@ -15,7 +15,7 @@ - + diff --git a/src/wroboarm_23/launch/moveit.rviz b/src/wroboarm_23/launch/moveit.rviz index 627612c8..d545f172 100644 --- a/src/wroboarm_23/launch/moveit.rviz +++ b/src/wroboarm_23/launch/moveit.rviz @@ -5,6 +5,7 @@ Panels: Property Tree Widget: Expanded: - /MotionPlanning1 + - /MotionPlanning1/Planning Request1 - /Pose1 Splitter Ratio: 0.5 Tree Height: 295 @@ -130,7 +131,7 @@ Visualization Manager: Interactive Marker Size: 0 Joint Violation Color: 255; 0; 255 Planning Group: arm - Query Goal State: true + Query Goal State: false Query Start State: false Show Workspace: false Start State Alpha: 1 diff --git a/test_arm_control_stack.sh b/test_arm_control_stack.sh index 3ebbc39f..af265954 100755 --- a/test_arm_control_stack.sh +++ b/test_arm_control_stack.sh @@ -11,8 +11,8 @@ cd $ROOT_DIR #done #rm ./out.temp; export WROVER_LOCAL=true -export WROVER_HW=REAL +export WROVER_HW=MOCK MOTOR_TO_INSPECT=11 -(sleep 2 && rqt_plot /control/arm/$MOTOR_TO_INSPECT/output /control/arm/$MOTOR_TO_INSPECT/setpoint /control/arm/$MOTOR_TO_INSPECT/feedback) & #/hsi/roboclaw/aux1/cmd/left +# (sleep 2 && rqt_plot /control/arm/$MOTOR_TO_INSPECT/output /control/arm/$MOTOR_TO_INSPECT/setpoint /control/arm/$MOTOR_TO_INSPECT/feedback) & #/hsi/roboclaw/aux1/cmd/left roslaunch wr_entry_point mock_arm.launch From 03839bfc4c808b5b6dee348b94a981de04a3346b Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 5 Dec 2022 19:48:40 -0600 Subject: [PATCH 14/33] Separated action server and joint state publisher into separate applications for arm control system --- .clang-format | 7 + .clang-tidy | 10 + .clangd | 2 + src/wr_control_drive_arm/CMakeLists.txt | 6 +- .../launch/actionserver.launch | 9 + .../launch/jointstatepublisher.launch | 9 + src/wr_control_drive_arm/launch/std.launch | 12 +- .../src/AbstractJoint.hpp | 10 + .../src/ArmControlActionServer.cpp | 248 ++++++++++++++++++ .../src/JointStatePublisher.cpp | 114 ++++++++ 10 files changed, 416 insertions(+), 11 deletions(-) create mode 100644 .clang-format create mode 100644 .clang-tidy create mode 100644 .clangd create mode 100644 src/wr_control_drive_arm/launch/actionserver.launch create mode 100644 src/wr_control_drive_arm/launch/jointstatepublisher.launch create mode 100644 src/wr_control_drive_arm/src/ArmControlActionServer.cpp create mode 100644 src/wr_control_drive_arm/src/JointStatePublisher.cpp diff --git a/.clang-format b/.clang-format new file mode 100644 index 00000000..c6ba5550 --- /dev/null +++ b/.clang-format @@ -0,0 +1,7 @@ +BasedOnStyle: LLVM +IndentWidth: 4 +AccessModifierOffset: -4 +CommentPragmas: 'NOLINT' +PackConstructorInitializers: CurrentLine +AlignOperands: AlignAfterOperator +AlignTrailingComments: true \ No newline at end of file diff --git a/.clang-tidy b/.clang-tidy new file mode 100644 index 00000000..e9f4e763 --- /dev/null +++ b/.clang-tidy @@ -0,0 +1,10 @@ +Checks: "bugprone-*,performance-*,readability-*,modernize-*,hicpp-*,cppcoreguidelines-*,clang-analyzer-*,-readability-braces-around-statements,-hicpp-braces-around-statements,-cppcoreguidelines-non-private-member-variables-in-classes" +WarningsAsErrors: '' +HeaderFilterRegex: '' +CheckOptions: + - key: readability-magic-numbers.IgnoredIntegerValues + value: '1;' + - key: hicpp-signed-bitwise.IgnorePositiveIntegerLiterals + value: 'true' + - key: readability-function-cognitive-complexity.IgnoreMacros + value: 'true' \ No newline at end of file diff --git a/.clangd b/.clangd new file mode 100644 index 00000000..538f880e --- /dev/null +++ b/.clangd @@ -0,0 +1,2 @@ +Diagnostics: + UnusedIncludes: Strict \ No newline at end of file diff --git a/src/wr_control_drive_arm/CMakeLists.txt b/src/wr_control_drive_arm/CMakeLists.txt index c9d43c92..19ef7fde 100644 --- a/src/wr_control_drive_arm/CMakeLists.txt +++ b/src/wr_control_drive_arm/CMakeLists.txt @@ -139,8 +139,10 @@ include_directories( ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide # add_executable(${PROJECT_NAME}_node src/wr_control_drive_arm_node.cpp) -add_executable(ArmControlSystem src/ArmControlSystem.cpp) -target_link_libraries(ArmControlSystem ${catkin_LIBRARIES} ${PROJECT_NAME}) +add_executable(ArmControlActionServer src/ArmControlActionServer.cpp) +target_link_libraries(ArmControlActionServer ${catkin_LIBRARIES} ${PROJECT_NAME}) +add_executable(JointStatePublisher src/JointStatePublisher.cpp) +target_link_libraries(JointStatePublisher ${catkin_LIBRARIES} ${PROJECT_NAME}) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the diff --git a/src/wr_control_drive_arm/launch/actionserver.launch b/src/wr_control_drive_arm/launch/actionserver.launch new file mode 100644 index 00000000..4ff64772 --- /dev/null +++ b/src/wr_control_drive_arm/launch/actionserver.launch @@ -0,0 +1,9 @@ + + + + + + + + + \ No newline at end of file diff --git a/src/wr_control_drive_arm/launch/jointstatepublisher.launch b/src/wr_control_drive_arm/launch/jointstatepublisher.launch new file mode 100644 index 00000000..eb85aac1 --- /dev/null +++ b/src/wr_control_drive_arm/launch/jointstatepublisher.launch @@ -0,0 +1,9 @@ + + + + + + + + + \ No newline at end of file diff --git a/src/wr_control_drive_arm/launch/std.launch b/src/wr_control_drive_arm/launch/std.launch index e9a2fb2f..96c2e726 100644 --- a/src/wr_control_drive_arm/launch/std.launch +++ b/src/wr_control_drive_arm/launch/std.launch @@ -1,11 +1,5 @@ + - - - - - - - - - + + diff --git a/src/wr_control_drive_arm/src/AbstractJoint.hpp b/src/wr_control_drive_arm/src/AbstractJoint.hpp index cf19f069..b395aa61 100644 --- a/src/wr_control_drive_arm/src/AbstractJoint.hpp +++ b/src/wr_control_drive_arm/src/AbstractJoint.hpp @@ -39,6 +39,16 @@ class AbstractJoint { void stopJoint(); + virtual ~AbstractJoint() = default; + + AbstractJoint(const AbstractJoint&) = delete; + + auto operator=(const AbstractJoint&) -> AbstractJoint& = delete; + + AbstractJoint(AbstractJoint&&) = delete; + + auto operator=(AbstractJoint&&) -> AbstractJoint& = delete; + protected: vector motors; }; diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp new file mode 100644 index 00000000..0e67d57b --- /dev/null +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -0,0 +1,248 @@ +/** + * @file ArmControlActionServer.cpp + * @author Ben Nowotny + * @brief The exeutable file to run the Arm Control Action Server + * @date 2021-04-05 + */ +#include "XmlRpcValue.h" + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "SimpleJoint.hpp" +#include "DifferentialJoint.hpp" +#include "ros/console.h" + +using XmlRpc::XmlRpcValue; + +/** + * @brief Refresh rate of ros::Rate + */ +constexpr float CLOCK_RATE = 50; + +constexpr double IK_WARN_RATE = 1.0/2; + +constexpr double JOINT_SAFETY_MAX_SPEED = 0.3; +constexpr double JOINT_SAFETY_HOLD_SPEED = 0.15; + +/** + * @brief Nessage cache size of publisher + */ +constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; + +/** + * @brief Period between timer callback + */ +constexpr float TIMER_CALLBACK_DURATION = 1.0 / 50.0; + +/** + * @brief Defines space for all Joint references + */ +constexpr int NUM_JOINTS = 5; +std::array, NUM_JOINTS> joints; +// AbstractJoint *joints[numJoints]; +/** + * @brief The Joint State Publisher for MoveIt + */ +ros::Publisher jointStatePublisher; +/** + * @brief Simplify the SimpleActionServer reference name + */ +typedef actionlib::SimpleActionServer Server; +/** + * @brief The service server for enabling IK + */ +ros::ServiceServer enableServiceServer; +/** + * @brief The status of IK program + */ +std::atomic_bool IKEnabled{true}; +/** + * @brief The service client for disabling IK + */ +ros::ServiceClient enableServiceClient; + +/** + * @brief Perform the given action as interpreted as moving the arm joints to specified positions + * + * @param goal The goal state given + * @param as The Action Server this is occuring on + */ +void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server* as) { + if (!IKEnabled) { + as->setAborted(); + ROS_WARN_THROTTLE(IK_WARN_RATE, "IK is disabled"); // NOLINT(hicpp-no-array-decay,hicpp,hicpp-vararg,cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + return; + } + + int currPoint = 1; + + std::cout << "start exec: " << goal->trajectory.points.size() << std::endl; + // For each point in the trajectory execution sequence... + for(const auto& name : goal->trajectory.joint_names){ + std::cout << name << "\t"; + } + std::cout << std::endl; + for(const auto &currTargetPosition : goal->trajectory.points){ + for(double pos : currTargetPosition.positions){ + std::cout << std::round(pos*100)/100 << "\t"; + } + std::cout << std::endl; + } + for(const auto &currTargetPosition : goal->trajectory.points){ + // Track whether or not the current position is done + bool hasPositionFinished = false; + // Keep max loop rate at 50 Hz + ros::Rate loop{CLOCK_RATE}; + + const double VELOCITY_MAX = abs(*std::max_element( + currTargetPosition.velocities.begin(), + currTargetPosition.velocities.end(), + [](double a, double b) -> bool{ return abs(a)trajectory.points.size() << std::endl; + currPoint++; + for(const auto &joint : joints){ + for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ + double velocity = VELOCITY_MAX == 0.F ? JOINT_SAFETY_HOLD_SPEED : currTargetPosition.velocities[currItr]/VELOCITY_MAX; + // std::cout << "config setpoint: " << currTargetPosition.positions[currItr] << ":" << velocity << std::endl; + joint->configSetpoint(i, currTargetPosition.positions[currItr], velocity); + currItr++; + } + joint->exectute(); + } + + // While the current position is not complete yet... + while(!hasPositionFinished){ + // Assume the current action is done until proven otherwise + hasPositionFinished = true; + // Create the Joint State message for the current update cycle + + // For each joint specified in the currTargetPosition... + for(const auto &joint : joints){ + + for(int k = 0; k < joint->getDegreesOfFreedom(); k++){ + // if (joint->getMotor(k)->getMotorState() == MotorState::MOVING) { + // std::cout << "Moving" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == MotorState::RUN_TO_TARGET) { + // std::cout << "Run to target" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { + // std::cout << "Stalling" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == MotorState::STOP) { + // std::cout << "Stop" << std::endl; + // } else { + // std::cout << "Error" << std::endl; + // } + + if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { + std::cout << "ACS stall detected" << std::endl; + IKEnabled = false; + std_srvs::Trigger srv; + if (enableServiceClient.call(srv)) { + ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + } else { + ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + } + } else { + hasPositionFinished &= joint->getMotor(k)->getMotorState() == MotorState::STOP; + } + // DEBUGGING OUTPUT: Print each motor's name, radian position, encoder position, and power + // std::cout<getEncoderCounts()<exectute(); + + // if (!joint->exectute()) { + // IKEnabled = false; + // std_srvs::Trigger srv; + // if (enableServiceClient.call(srv)) { + // ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + // } else { + // ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + // } + // return; + // } + } + // Sleep until the next update cycle + loop.sleep(); + } + } + + //When all positions have been reached, set the current task as succeeded + + as->setSucceeded(); +} + +/** + * @brief publishes the arm's position + */ +void publishJointStates(const ros::TimerEvent &event){ + std::vector names; + std::vector positions; + sensor_msgs::JointState js_msg; + + for(const auto &joint : joints){ + for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ + names.push_back(joint->getMotor(i)->getMotorName()); + positions.push_back(joint->getMotor(i)->getRads()); + } + } + + js_msg.name = names; + js_msg.position = positions; + js_msg.header.stamp = ros::Time::now(); + // Publish the Joint State message + jointStatePublisher.publish(js_msg); +} + +/** + * @brief The main executable method of the node. Starts the ROS node and the Action Server for processing Arm Control commands + * + * @param argc The number of program arguments + * @param argv The given program arguments + * @return int The status code on exiting the program + */ +auto main(int argc, char** argv) ->int +{ + std::cout << "start main" << std::endl; + // Initialize the current node as ArmControlSystem + ros::init(argc, argv, "ArmControlActionServer"); + // Create the NodeHandle to the current ROS node + ros::NodeHandle n; + + // Initialize the Action Server + Server server(n, "/arm_controller/follow_joint_trajectory", boost::bind(&execute, _1, &server), false); + // Start the Action Server + server.start(); + std::cout << "server started" << std::endl; + + enableServiceServer = n.advertiseService("start_IK", + static_cast>( + [](std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)->bool{ + IKEnabled = true; + res.message = "Arm IK Enabled"; + res.success = static_cast(true); + return true; + } + )); + + enableServiceClient = n.serviceClient("PLACEHOLDER_NAME"); + + std::cout << "entering ROS spin..." << std::endl; + // ROS spin for communication with other nodes + ros::spin(); + // Return 0 on exit (successful exit) + return 0; +} diff --git a/src/wr_control_drive_arm/src/JointStatePublisher.cpp b/src/wr_control_drive_arm/src/JointStatePublisher.cpp new file mode 100644 index 00000000..b6d47251 --- /dev/null +++ b/src/wr_control_drive_arm/src/JointStatePublisher.cpp @@ -0,0 +1,114 @@ +/** + * @file JointStatePublisher.cpp + * @author Ben Nowotny + * @author Jack Zautner + * @brief The executable file to run the joint state publisher + * @date 2022-12-05 + */ +#include "XmlRpcValue.h" + +#include "ros/ros.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "SimpleJoint.hpp" +#include "DifferentialJoint.hpp" +#include "ros/console.h" + +using XmlRpc::XmlRpcValue; + +/** + * @brief Nessage cache size of publisher + */ +constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; + +/** + * @brief Period between timer callback + */ +constexpr float TIMER_CALLBACK_DURATION = 1.0 / 50.0; + +/** + * @brief Defines space for all Joint references + */ +constexpr int NUM_JOINTS = 5; +std::array, NUM_JOINTS> joints; + +/** + * @brief The joint state publisher for MoveIt + */ +ros::Publisher jointStatePublisher; + +void publishJointStates(const ros::TimerEvent &event){ + std::vector names; + std::vector positions; + sensor_msgs::JointState js_msg; + + for(const auto &joint : joints){ + for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ + names.push_back(joint->getMotor(i)->getMotorName()); + positions.push_back(joint->getMotor(i)->getRads()); + } + } + + js_msg.name = names; + js_msg.position = positions; + js_msg.header.stamp = ros::Time::now(); + // Publish the Joint State message + jointStatePublisher.publish(js_msg); +} + +/** + * @brief The main executable method of the node. Starts the ROS node + * + * @param argc The number of program arguments + * @param argv The given program arguments + * @return int The status code on exiting the program + */ +auto main(int argc, char** argv) -> int { + + std::cout << "start main" << std::endl; + // Initialize the current node as JointStatePublisherApplication + ros::init(argc, argv, "JointStatePublisher"); + // Create the NodeHandle to the current ROS node + ros::NodeHandle n; + ros::NodeHandle pn{"~"}; + + XmlRpcValue encParams; + pn.getParam("encoder_parameters", encParams); + + // Initialize all motors with their MoveIt name, WRoboclaw initialization, and reference to the current node + auto elbowPitch_joint = std::make_unique("elbowPitch_joint", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n); + auto elbowRoll_joint = std::make_unique("elbowRoll_joint", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n); + auto shoulder_joint = std::make_unique("shoulder_joint", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n); + auto turntable_joint = std::make_unique("turntable_joint", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n); + auto wristPitch_joint = std::make_unique("wristPitch_joint", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n); + auto wristRoll_link = std::make_unique("wristRoll_link", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n); + std::cout << "init motors" << std::endl; + + // Initialize all Joints + joints.at(0) = std::make_unique(std::move(elbowPitch_joint), n); + joints.at(1) = std::make_unique(std::move(elbowRoll_joint), n); + joints.at(2) = std::make_unique(std::move(shoulder_joint), n); + joints.at(3) = std::make_unique(std::move(turntable_joint), n); + joints.at(4) = std::make_unique(std::move(wristPitch_joint), std::move(wristRoll_link), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); + std::cout << "init joints" << std::endl; + + // Initialize the Joint State Data Publisher + jointStatePublisher = n.advertise("/joint_states", MESSAGE_CACHE_SIZE); + + // Timer that will call publishJointStates periodically + ros::Timer timer = n.createTimer(ros::Duration(TIMER_CALLBACK_DURATION), publishJointStates); + + // Enter ROS spin + ros::spin(); + + return 0; +} \ No newline at end of file From 1fc442f3557c6b8c1654251c04f52af97e004894 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 5 Dec 2022 19:51:18 -0600 Subject: [PATCH 15/33] Deleted old ArmControlSystem file --- .../src/ArmControlSystem.cpp | 274 ------------------ 1 file changed, 274 deletions(-) delete mode 100644 src/wr_control_drive_arm/src/ArmControlSystem.cpp diff --git a/src/wr_control_drive_arm/src/ArmControlSystem.cpp b/src/wr_control_drive_arm/src/ArmControlSystem.cpp deleted file mode 100644 index a7681e89..00000000 --- a/src/wr_control_drive_arm/src/ArmControlSystem.cpp +++ /dev/null @@ -1,274 +0,0 @@ -/** - * @file ArmControlSystem.cpp - * @author Ben Nowotny - * @brief The exeutable file to run the Arm Control Action Server - * @date 2021-04-05 - */ -#include "XmlRpcValue.h" - -#include "ros/ros.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "SimpleJoint.hpp" -#include "DifferentialJoint.hpp" -#include "ros/console.h" - -using XmlRpc::XmlRpcValue; - -/** - * @brief Refresh rate of ros::Rate - */ -constexpr float CLOCK_RATE = 50; - -constexpr double IK_WARN_RATE = 1.0/2; - -constexpr double JOINT_SAFETY_MAX_SPEED = 0.3; -constexpr double JOINT_SAFETY_HOLD_SPEED = 0.15; - -/** - * @brief Nessage cache size of publisher - */ -constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; - -/** - * @brief Period between timer callback - */ -constexpr float TIMER_CALLBACK_DURATION = 1.0 / 50.0; - -/** - * @brief Defines space for all Joint references - */ -constexpr int NUM_JOINTS = 5; -std::array, NUM_JOINTS> joints; -// AbstractJoint *joints[numJoints]; -/** - * @brief The Joint State Publisher for MoveIt - */ -ros::Publisher jointStatePublisher; -/** - * @brief Simplify the SimpleActionServer reference name - */ -typedef actionlib::SimpleActionServer Server; -/** - * @brief The service server for enabling IK - */ -ros::ServiceServer enableServiceServer; -/** - * @brief The status of IK program - */ -std::atomic_bool IKEnabled{true}; -/** - * @brief The service client for disabling IK - */ -ros::ServiceClient enableServiceClient; - -/** - * @brief Perform the given action as interpreted as moving the arm joints to specified positions - * - * @param goal The goal state given - * @param as The Action Server this is occuring on - */ -void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server* as) { - if (!IKEnabled) { - as->setAborted(); - ROS_WARN_THROTTLE(IK_WARN_RATE, "IK is disabled"); // NOLINT(hicpp-no-array-decay,hicpp,hicpp-vararg,cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - return; - } - - int currPoint = 1; - - std::cout << "start exec: " << goal->trajectory.points.size() << std::endl; - // For each point in the trajectory execution sequence... - for(const auto& name : goal->trajectory.joint_names){ - std::cout << name << "\t"; - } - std::cout << std::endl; - for(const auto &currTargetPosition : goal->trajectory.points){ - for(double pos : currTargetPosition.positions){ - std::cout << std::round(pos*100)/100 << "\t"; - } - std::cout << std::endl; - } - for(const auto &currTargetPosition : goal->trajectory.points){ - // Track whether or not the current position is done - bool hasPositionFinished = false; - // Keep max loop rate at 50 Hz - ros::Rate loop{CLOCK_RATE}; - - const double VELOCITY_MAX = abs(*std::max_element( - currTargetPosition.velocities.begin(), - currTargetPosition.velocities.end(), - [](double a, double b) -> bool{ return abs(a)trajectory.points.size() << std::endl; - currPoint++; - for(const auto &joint : joints){ - for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ - double velocity = VELOCITY_MAX == 0.F ? JOINT_SAFETY_HOLD_SPEED : currTargetPosition.velocities[currItr]/VELOCITY_MAX; - // std::cout << "config setpoint: " << currTargetPosition.positions[currItr] << ":" << velocity << std::endl; - joint->configSetpoint(i, currTargetPosition.positions[currItr], velocity); - currItr++; - } - joint->exectute(); - } - - // While the current position is not complete yet... - while(!hasPositionFinished){ - // Assume the current action is done until proven otherwise - hasPositionFinished = true; - // Create the Joint State message for the current update cycle - - // For each joint specified in the currTargetPosition... - for(const auto &joint : joints){ - - for(int k = 0; k < joint->getDegreesOfFreedom(); k++){ - // if (joint->getMotor(k)->getMotorState() == MotorState::MOVING) { - // std::cout << "Moving" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == MotorState::RUN_TO_TARGET) { - // std::cout << "Run to target" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { - // std::cout << "Stalling" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == MotorState::STOP) { - // std::cout << "Stop" << std::endl; - // } else { - // std::cout << "Error" << std::endl; - // } - - if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { - std::cout << "ACS stall detected" << std::endl; - IKEnabled = false; - std_srvs::Trigger srv; - if (enableServiceClient.call(srv)) { - ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - } else { - ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - } - } else { - hasPositionFinished &= joint->getMotor(k)->getMotorState() == MotorState::STOP; - } - // DEBUGGING OUTPUT: Print each motor's name, radian position, encoder position, and power - // std::cout<getEncoderCounts()<exectute(); - - // if (!joint->exectute()) { - // IKEnabled = false; - // std_srvs::Trigger srv; - // if (enableServiceClient.call(srv)) { - // ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - // } else { - // ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - // } - // return; - // } - } - // Sleep until the next update cycle - loop.sleep(); - } - } - - //When all positions have been reached, set the current task as succeeded - - as->setSucceeded(); -} - -/** - * @brief publishes the arm's position - */ -void publishJointStates(const ros::TimerEvent &event){ - std::vector names; - std::vector positions; - sensor_msgs::JointState js_msg; - - for(const auto &joint : joints){ - for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ - names.push_back(joint->getMotor(i)->getMotorName()); - positions.push_back(joint->getMotor(i)->getRads()); - } - } - - js_msg.name = names; - js_msg.position = positions; - js_msg.header.stamp = ros::Time::now(); - // Publish the Joint State message - jointStatePublisher.publish(js_msg); -} - -/** - * @brief The main executable method of the node. Starts the ROS node and the Action Server for processing Arm Control commands - * - * @param argc The number of program arguments - * @param argv The given program arguments - * @return int The status code on exiting the program - */ -auto main(int argc, char** argv) ->int -{ - std::cout << "start main" << std::endl; - // Initialize the current node as ArmControlSystem - ros::init(argc, argv, "ArmControlSystem"); - // Create the NodeHandle to the current ROS node - ros::NodeHandle n; - ros::NodeHandle pn{"~"}; - - XmlRpcValue encParams; - pn.getParam("encoder_parameters", encParams); - - // Initialize all motors with their MoveIt name, WRoboclaw initialization, and reference to the current node - auto elbowPitch_joint = std::make_unique("elbowPitch_joint", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n); - auto elbowRoll_joint = std::make_unique("elbowRoll_joint", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n); - auto shoulder_joint = std::make_unique("shoulder_joint", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n); - auto turntable_joint = std::make_unique("turntable_joint", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n); - auto wristPitch_joint = std::make_unique("wristPitch_joint", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n); - auto wristRoll_link = std::make_unique("wristRoll_link", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n); - std::cout << "init motors" << std::endl; - - // Initialize all Joints - joints.at(3) = std::make_unique(std::move(turntable_joint), n); - joints.at(2) = std::make_unique(std::move(shoulder_joint), n); - joints.at(0) = std::make_unique(std::move(elbowPitch_joint), n); - joints.at(1) = std::make_unique(std::move(elbowRoll_joint), n); - joints.at(4) = std::make_unique(std::move(wristPitch_joint), std::move(wristRoll_link), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); - std::cout << "init joints" << std::endl; - - // Initialize the Joint State Data Publisher - jointStatePublisher = n.advertise("/joint_states", MESSAGE_CACHE_SIZE); - - // Initialize the Action Server - Server server(n, "/arm_controller/follow_joint_trajectory", boost::bind(&execute, _1, &server), false); - // Start the Action Server - server.start(); - std::cout << "server started" << std::endl; - - ros::Timer timer = n.createTimer(ros::Duration(TIMER_CALLBACK_DURATION), publishJointStates); - - enableServiceServer = n.advertiseService("start_IK", - static_cast>( - [](std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)->bool{ - IKEnabled = true; - res.message = "Arm IK Enabled"; - res.success = static_cast(true); - return true; - } - )); - - enableServiceClient = n.serviceClient("PLACEHOLDER_NAME"); - - std::cout << "entering ROS spin..." << std::endl; - // ROS spin for communication with other nodes - ros::spin(); - // Return 0 on exit (successful exit) - return 0; -} From a78de45c88225e1b05b0fdfe58ccc0b8b0e8ad20 Mon Sep 17 00:00:00 2001 From: Arthur Date: Mon, 5 Dec 2022 17:56:21 -0800 Subject: [PATCH 16/33] WIP on joint limits --- .../config/arm_motor_PID_mock.yaml | 64 +++++++++++++++++++ ...motor_PID.yaml => arm_motor_PID_real.yaml} | 2 +- src/wr_control_drive_arm/launch/std.launch | 3 +- src/wroboarm_23/config/joint_limits.yaml | 64 +++++++++++-------- src/wroboarm_23/launch/moveit.rviz | 4 +- .../launch/trajectory_execution.launch.xml | 2 +- src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf | 18 ++++-- test_arm_control_stack.sh | 2 +- 8 files changed, 121 insertions(+), 38 deletions(-) create mode 100644 src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml rename src/wr_control_drive_arm/config/{arm_motor_PID.yaml => arm_motor_PID_real.yaml} (99%) diff --git a/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml b/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml new file mode 100644 index 00000000..88d33a6e --- /dev/null +++ b/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml @@ -0,0 +1,64 @@ +rate: 50 +controllers: + - setpointTopic: "/control/arm/00/setpoint" + feedbackTopic: "/control/arm/00/feedback" + outputTopic: "/control/arm/00/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 + + - setpointTopic: "/control/arm/01/setpoint" + feedbackTopic: "/control/arm/01/feedback" + outputTopic: "/control/arm/01/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 + + - setpointTopic: "/control/arm/10/setpoint" + feedbackTopic: "/control/arm/10/feedback" + outputTopic: "/control/arm/10/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 + + - setpointTopic: "/control/arm/11/setpoint" + feedbackTopic: "/control/arm/11/feedback" + outputTopic: "/control/arm/11/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 + + - setpointTopic: "/control/arm/20/setpoint" + feedbackTopic: "/control/arm/20/feedback" + outputTopic: "/control/arm/20/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 + + - setpointTopic: "/control/arm/21/setpoint" + feedbackTopic: "/control/arm/21/feedback" + outputTopic: "/control/arm/21/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 + + - setpointTopic: "/control/arm/3000/setpoint" + feedbackTopic: "/control/arm/3000/feedback" + outputTopic: "/control/arm/3000/output" + P: 100 + I: 0 + D: 0 + min: -1 + max: 1 diff --git a/src/wr_control_drive_arm/config/arm_motor_PID.yaml b/src/wr_control_drive_arm/config/arm_motor_PID_real.yaml similarity index 99% rename from src/wr_control_drive_arm/config/arm_motor_PID.yaml rename to src/wr_control_drive_arm/config/arm_motor_PID_real.yaml index 33ec8ae2..108c62f4 100644 --- a/src/wr_control_drive_arm/config/arm_motor_PID.yaml +++ b/src/wr_control_drive_arm/config/arm_motor_PID_real.yaml @@ -3,7 +3,7 @@ controllers: - setpointTopic: "/control/arm/00/setpoint" feedbackTopic: "/control/arm/00/feedback" outputTopic: "/control/arm/00/output" - P: 5 + P: 5 I: 0 D: 0 min: -1 diff --git a/src/wr_control_drive_arm/launch/std.launch b/src/wr_control_drive_arm/launch/std.launch index e9a2fb2f..8d5d412f 100644 --- a/src/wr_control_drive_arm/launch/std.launch +++ b/src/wr_control_drive_arm/launch/std.launch @@ -1,7 +1,8 @@ - + + diff --git a/src/wroboarm_23/config/joint_limits.yaml b/src/wroboarm_23/config/joint_limits.yaml index e565424c..2454284c 100644 --- a/src/wroboarm_23/config/joint_limits.yaml +++ b/src/wroboarm_23/config/joint_limits.yaml @@ -2,39 +2,51 @@ # 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 +default_velocity_scaling_factor: 1.0 +default_acceleration_scaling_factor: 1.0 # 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: elbowPitch_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 + has_velocity_limits: true + max_velocity: 10 + has_acceleration_limits: true + max_acceleration: 10 + max_position: !radians pi + min_position: !radians 0 elbowRoll_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 + has_velocity_limits: true + max_velocity: 10 + has_acceleration_limits: true + max_acceleration: 10 + max_position: !radians pi / 2 + min_position: !radians -pi / 2 shoulder_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 + has_velocity_limits: true + max_velocity: 10 + has_acceleration_limits: true + max_acceleration: 10 + max_position: !radians 0 + min_position: !radians -pi turntable_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 + has_velocity_limits: true + max_velocity: 10 + has_acceleration_limits: true + max_acceleration: 10 + max_position: !radians pi / 2 + min_position: !radians 0 wristPitch_joint: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 + has_velocity_limits: true + max_velocity: 10 + has_acceleration_limits: true + max_acceleration: 10 + max_position: !radians pi + min_position: !radians 0 wristRoll_link: - has_velocity_limits: false - max_velocity: 0 - has_acceleration_limits: false - max_acceleration: 0 \ No newline at end of file + has_velocity_limits: true + max_velocity: 10 + has_acceleration_limits: true + max_acceleration: 10 + max_position: !radians pi / 2 + min_position: !radians -pi / 2 \ No newline at end of file diff --git a/src/wroboarm_23/launch/moveit.rviz b/src/wroboarm_23/launch/moveit.rviz index d545f172..97d51153 100644 --- a/src/wroboarm_23/launch/moveit.rviz +++ b/src/wroboarm_23/launch/moveit.rviz @@ -111,7 +111,7 @@ Visualization Manager: Robot Alpha: 0.5 Robot Color: 150; 50; 150 Show Robot Collision: false - Show Robot Visual: true + Show Robot Visual: false Show Trail: false State Display Time: 0.05 s Trail Step Size: 1 @@ -188,7 +188,7 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true - Robot Alpha: 0.5 + Robot Alpha: 0.85 Show Robot Collision: false Show Robot Visual: true Value: true diff --git a/src/wroboarm_23/launch/trajectory_execution.launch.xml b/src/wroboarm_23/launch/trajectory_execution.launch.xml index 20c3dfc4..a2841558 100644 --- a/src/wroboarm_23/launch/trajectory_execution.launch.xml +++ b/src/wroboarm_23/launch/trajectory_execution.launch.xml @@ -12,7 +12,7 @@ - + diff --git a/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf b/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf index 9f023c40..3bd1ee46 100644 --- a/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf +++ b/src/wroboarm_23/urdf/ArmAssembly.SLDASM.urdf @@ -86,7 +86,7 @@ + type="revolute"> @@ -96,6 +96,7 @@ link="turntable_link" /> + @@ -139,7 +140,7 @@ + type="revolute"> @@ -149,6 +150,7 @@ link="upperArm_link" /> + @@ -192,7 +194,7 @@ + type="revolute"> @@ -202,6 +204,7 @@ link="forearm_link" /> + @@ -245,7 +248,7 @@ + type="revolute"> @@ -255,6 +258,7 @@ link="wrist_link" /> + @@ -298,7 +302,7 @@ + type="revolute"> @@ -308,6 +312,7 @@ link="carpus_link" /> + @@ -351,7 +356,7 @@ + type="revolute"> @@ -361,5 +366,6 @@ link="endEffector_link" /> + \ No newline at end of file diff --git a/test_arm_control_stack.sh b/test_arm_control_stack.sh index af265954..3238d1ac 100755 --- a/test_arm_control_stack.sh +++ b/test_arm_control_stack.sh @@ -11,7 +11,7 @@ cd $ROOT_DIR #done #rm ./out.temp; export WROVER_LOCAL=true -export WROVER_HW=MOCK +export WROVER_HW=REAL MOTOR_TO_INSPECT=11 # (sleep 2 && rqt_plot /control/arm/$MOTOR_TO_INSPECT/output /control/arm/$MOTOR_TO_INSPECT/setpoint /control/arm/$MOTOR_TO_INSPECT/feedback) & #/hsi/roboclaw/aux1/cmd/left roslaunch wr_entry_point mock_arm.launch From 9511729325c4ca8c1cf4a4da8c5fe4c8ca1faf55 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Wed, 7 Dec 2022 17:55:37 -0600 Subject: [PATCH 17/33] Fixed date in header --- src/wr_control_drive_arm/src/ArmControlActionServer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 0e67d57b..a178f157 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -2,7 +2,7 @@ * @file ArmControlActionServer.cpp * @author Ben Nowotny * @brief The exeutable file to run the Arm Control Action Server - * @date 2021-04-05 + * @date 2022-12-05 */ #include "XmlRpcValue.h" From 901aa7ce4592b827e325977b5514af12adf625ae Mon Sep 17 00:00:00 2001 From: Ben Nowotny Date: Sun, 22 Jan 2023 19:20:31 -0600 Subject: [PATCH 18/33] Fixed some of the arm code to run the controller and the jsp at the same time. --- .vscode/settings.json | 3 +- .../launch/actionserver.launch | 16 +- .../src/ArmControlActionServer.cpp | 394 ++++++++------- src/wr_control_drive_arm/src/ArmMotor.cpp | 139 +++--- src/wr_control_drive_arm/src/ArmMotor.hpp | 447 +++++++++--------- .../src/JointStatePublisher.cpp | 68 +-- test_arm_control_stack.sh | 2 +- 7 files changed, 593 insertions(+), 476 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index f7c28a84..772e1688 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -88,5 +88,6 @@ "python.analysis.extraPaths": [ "/home/nomorenickels/Documents/WRover_Software/devel/lib/python3/dist-packages", "/opt/ros/noetic/lib/python3/dist-packages" - ] + ], + "cmake.sourceDirectory": "${workspaceFolder}/src" } \ No newline at end of file diff --git a/src/wr_control_drive_arm/launch/actionserver.launch b/src/wr_control_drive_arm/launch/actionserver.launch index 4ff64772..115c85dd 100644 --- a/src/wr_control_drive_arm/launch/actionserver.launch +++ b/src/wr_control_drive_arm/launch/actionserver.launch @@ -2,8 +2,20 @@ - + + + + + - \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index a178f157..29fdc34f 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -6,21 +6,21 @@ */ #include "XmlRpcValue.h" +#include "DifferentialJoint.hpp" +#include "SimpleJoint.hpp" +#include "ros/console.h" #include "ros/ros.h" -#include #include -#include -#include -#include #include -#include -#include #include +#include +#include #include +#include +#include +#include #include -#include "SimpleJoint.hpp" -#include "DifferentialJoint.hpp" -#include "ros/console.h" +#include using XmlRpc::XmlRpcValue; @@ -29,7 +29,7 @@ using XmlRpc::XmlRpcValue; */ constexpr float CLOCK_RATE = 50; -constexpr double IK_WARN_RATE = 1.0/2; +constexpr double IK_WARN_RATE = 1.0 / 2; constexpr double JOINT_SAFETY_MAX_SPEED = 0.3; constexpr double JOINT_SAFETY_HOLD_SPEED = 0.15; @@ -37,7 +37,7 @@ constexpr double JOINT_SAFETY_HOLD_SPEED = 0.15; /** * @brief Nessage cache size of publisher */ -constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; +constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; /** * @brief Period between timer callback @@ -57,7 +57,8 @@ ros::Publisher jointStatePublisher; /** * @brief Simplify the SimpleActionServer reference name */ -typedef actionlib::SimpleActionServer Server; +typedef actionlib::SimpleActionServer + Server; /** * @brief The service server for enabling IK */ @@ -72,177 +73,250 @@ std::atomic_bool IKEnabled{true}; ros::ServiceClient enableServiceClient; /** - * @brief Perform the given action as interpreted as moving the arm joints to specified positions - * + * @brief Perform the given action as interpreted as moving the arm joints to + * specified positions + * * @param goal The goal state given * @param as The Action Server this is occuring on */ -void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal, Server* as) { - if (!IKEnabled) { - as->setAborted(); - ROS_WARN_THROTTLE(IK_WARN_RATE, "IK is disabled"); // NOLINT(hicpp-no-array-decay,hicpp,hicpp-vararg,cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - return; - } - - int currPoint = 1; - - std::cout << "start exec: " << goal->trajectory.points.size() << std::endl; - // For each point in the trajectory execution sequence... - for(const auto& name : goal->trajectory.joint_names){ - std::cout << name << "\t"; - } - std::cout << std::endl; - for(const auto &currTargetPosition : goal->trajectory.points){ - for(double pos : currTargetPosition.positions){ - std::cout << std::round(pos*100)/100 << "\t"; - } +void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, + Server *as) { + if (!IKEnabled) { + as->setAborted(); + ROS_WARN_THROTTLE( + IK_WARN_RATE, + "IK is disabled"); // NOLINT(hicpp-no-array-decay,hicpp,hicpp-vararg,cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + return; + } + + int currPoint = 1; + + std::cout << "start exec: " << goal->trajectory.points.size() << std::endl; + // For each point in the trajectory execution sequence... + for (const auto &name : goal->trajectory.joint_names) { + std::cout << name << "\t"; + } std::cout << std::endl; - } - for(const auto &currTargetPosition : goal->trajectory.points){ - // Track whether or not the current position is done - bool hasPositionFinished = false; - // Keep max loop rate at 50 Hz - ros::Rate loop{CLOCK_RATE}; - - const double VELOCITY_MAX = abs(*std::max_element( - currTargetPosition.velocities.begin(), - currTargetPosition.velocities.end(), - [](double a, double b) -> bool{ return abs(a)trajectory.points.size() << std::endl; - currPoint++; - for(const auto &joint : joints){ - for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ - double velocity = VELOCITY_MAX == 0.F ? JOINT_SAFETY_HOLD_SPEED : currTargetPosition.velocities[currItr]/VELOCITY_MAX; - // std::cout << "config setpoint: " << currTargetPosition.positions[currItr] << ":" << velocity << std::endl; - joint->configSetpoint(i, currTargetPosition.positions[currItr], velocity); - currItr++; - } - joint->exectute(); + for (const auto &currTargetPosition : goal->trajectory.points) { + for (double pos : currTargetPosition.positions) { + std::cout << std::round(pos * 100) / 100 << "\t"; + } + std::cout << std::endl; } + for (const auto &currTargetPosition : goal->trajectory.points) { + // Track whether or not the current position is done + bool hasPositionFinished = false; + // Keep max loop rate at 50 Hz + ros::Rate loop{CLOCK_RATE}; + + const double VELOCITY_MAX = abs(*std::max_element( + currTargetPosition.velocities.begin(), + currTargetPosition.velocities.end(), + [](double a, double b) -> bool { return abs(a) < abs(b); })); - // While the current position is not complete yet... - while(!hasPositionFinished){ - // Assume the current action is done until proven otherwise - hasPositionFinished = true; - // Create the Joint State message for the current update cycle - - // For each joint specified in the currTargetPosition... - for(const auto &joint : joints){ - - for(int k = 0; k < joint->getDegreesOfFreedom(); k++){ - // if (joint->getMotor(k)->getMotorState() == MotorState::MOVING) { - // std::cout << "Moving" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == MotorState::RUN_TO_TARGET) { - // std::cout << "Run to target" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { - // std::cout << "Stalling" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == MotorState::STOP) { - // std::cout << "Stop" << std::endl; - // } else { - // std::cout << "Error" << std::endl; - // } - - if (joint->getMotor(k)->getMotorState() == MotorState::STALLING) { - std::cout << "ACS stall detected" << std::endl; - IKEnabled = false; - std_srvs::Trigger srv; - if (enableServiceClient.call(srv)) { - ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - } else { - ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + ArmMotor *currmotor = NULL; + int currItr = 0; + // std::cout << currPoint << " / " << goal->trajectory.points.size() << + // std::endl; + currPoint++; + for (const auto &joint : joints) { + for (int i = 0; i < joint->getDegreesOfFreedom(); i++) { + double velocity = + VELOCITY_MAX == 0.F + ? JOINT_SAFETY_HOLD_SPEED + : currTargetPosition.velocities[currItr] / VELOCITY_MAX; + // std::cout << "config setpoint: " << + // currTargetPosition.positions[currItr] << ":" << velocity << + // std::endl; + joint->configSetpoint(i, currTargetPosition.positions[currItr], + velocity); + currItr++; } - } else { - hasPositionFinished &= joint->getMotor(k)->getMotorState() == MotorState::STOP; - } - // DEBUGGING OUTPUT: Print each motor's name, radian position, encoder position, and power - // std::cout<getEncoderCounts()<exectute(); } - joint->exectute(); - - // if (!joint->exectute()) { - // IKEnabled = false; - // std_srvs::Trigger srv; - // if (enableServiceClient.call(srv)) { - // ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - // } else { - // ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - // } - // return; - // } - } - // Sleep until the next update cycle - loop.sleep(); + // While the current position is not complete yet... + while (!hasPositionFinished) { + // Assume the current action is done until proven otherwise + hasPositionFinished = true; + // Create the Joint State message for the current update cycle + + // For each joint specified in the currTargetPosition... + for (const auto &joint : joints) { + + for (int k = 0; k < joint->getDegreesOfFreedom(); k++) { + // if (joint->getMotor(k)->getMotorState() == + // MotorState::MOVING) { + // std::cout << "Moving" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == + // MotorState::RUN_TO_TARGET) { + // std::cout << "Run to target" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == + // MotorState::STALLING) { + // std::cout << "Stalling" << std::endl; + // } else if (joint->getMotor(k)->getMotorState() == + // MotorState::STOP) { + // std::cout << "Stop" << std::endl; + // } else { + // std::cout << "Error" << std::endl; + // } + + if (joint->getMotor(k)->getMotorState() == + MotorState::STALLING) { + std::cout << "ACS stall detected" << std::endl; + IKEnabled = false; + std_srvs::Trigger srv; + if (enableServiceClient.call(srv)) { + ROS_WARN( + "%s", + (std::string{"PLACEHOLDER_NAME: "} + + srv.response.message) + .data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + } else { + ROS_WARN( + "Error: failed to call service " + "PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + } + } else { + hasPositionFinished &= + joint->getMotor(k)->getMotorState() == + MotorState::STOP; + } + // DEBUGGING OUTPUT: Print each motor's name, radian + // position, encoder position, and power + // std::cout << std::setw(30) << joint->getMotor(k)->getRads() + // << std::endl; + } + + joint->exectute(); + + // if (!joint->exectute()) { + // IKEnabled = false; + // std_srvs::Trigger srv; + // if (enableServiceClient.call(srv)) { + // ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + // } else { + // ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + // } + // return; + // } + } + // Sleep until the next update cycle + loop.sleep(); + } } - } - //When all positions have been reached, set the current task as succeeded - - as->setSucceeded(); + // When all positions have been reached, set the current task as succeeded + + as->setSucceeded(); } /** * @brief publishes the arm's position */ -void publishJointStates(const ros::TimerEvent &event){ - std::vector names; - std::vector positions; - sensor_msgs::JointState js_msg; - - for(const auto &joint : joints){ - for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ - names.push_back(joint->getMotor(i)->getMotorName()); - positions.push_back(joint->getMotor(i)->getRads()); +void publishJointStates(const ros::TimerEvent &event) { + std::vector names; + std::vector positions; + sensor_msgs::JointState js_msg; + + for (const auto &joint : joints) { + for (int i = 0; i < joint->getDegreesOfFreedom(); i++) { + names.push_back(joint->getMotor(i)->getMotorName()); + positions.push_back(joint->getMotor(i)->getRads()); + } } - } - js_msg.name = names; - js_msg.position = positions; - js_msg.header.stamp = ros::Time::now(); - // Publish the Joint State message - jointStatePublisher.publish(js_msg); + js_msg.name = names; + js_msg.position = positions; + js_msg.header.stamp = ros::Time::now(); + // Publish the Joint State message + jointStatePublisher.publish(js_msg); } /** - * @brief The main executable method of the node. Starts the ROS node and the Action Server for processing Arm Control commands - * + * @brief The main executable method of the node. Starts the ROS node and the + * Action Server for processing Arm Control commands + * * @param argc The number of program arguments * @param argv The given program arguments * @return int The status code on exiting the program */ -auto main(int argc, char** argv) ->int -{ - std::cout << "start main" << std::endl; - // Initialize the current node as ArmControlSystem - ros::init(argc, argv, "ArmControlActionServer"); - // Create the NodeHandle to the current ROS node - ros::NodeHandle n; - - // Initialize the Action Server - Server server(n, "/arm_controller/follow_joint_trajectory", boost::bind(&execute, _1, &server), false); - // Start the Action Server - server.start(); - std::cout << "server started" << std::endl; - - enableServiceServer = n.advertiseService("start_IK", - static_cast>( - [](std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)->bool{ - IKEnabled = true; - res.message = "Arm IK Enabled"; - res.success = static_cast(true); - return true; - } - )); - - enableServiceClient = n.serviceClient("PLACEHOLDER_NAME"); - - std::cout << "entering ROS spin..." << std::endl; - // ROS spin for communication with other nodes - ros::spin(); - // Return 0 on exit (successful exit) - return 0; +auto main(int argc, char **argv) -> int { + std::cout << "start main" << std::endl; + // Initialize the current node as ArmControlSystem + ros::init(argc, argv, "ArmControlActionServer"); + // Create the NodeHandle to the current ROS node + ros::NodeHandle n; + ros::NodeHandle pn{"~"}; + + XmlRpcValue encParams; + pn.getParam("encoder_parameters", encParams); + + // Initialize all motors with their MoveIt name, WRoboclaw initialization, + // and reference to the current node + auto elbowPitch_joint = std::make_unique( + "elbowPitch_joint", 1, 0, + static_cast(encParams[0]["counts_per_rotation"]), + static_cast(encParams[0]["offset"]), n); + auto elbowRoll_joint = std::make_unique( + "elbowRoll_joint", 1, 1, + static_cast(encParams[1]["counts_per_rotation"]), + static_cast(encParams[1]["offset"]), n); + auto shoulder_joint = std::make_unique( + "shoulder_joint", 0, 1, + static_cast(encParams[2]["counts_per_rotation"]), + static_cast(encParams[2]["offset"]), n); + auto turntable_joint = std::make_unique( + "turntable_joint", 0, 0, + static_cast(encParams[3]["counts_per_rotation"]), + static_cast(encParams[3]["offset"]), n); + auto wristPitch_joint = std::make_unique( + "wristPitch_joint", 2, 0, + static_cast(encParams[4]["counts_per_rotation"]), + static_cast(encParams[4]["offset"]), n); + auto wristRoll_link = std::make_unique( + "wristRoll_link", 2, 1, + static_cast(encParams[5]["counts_per_rotation"]), + static_cast(encParams[5]["offset"]), n); + std::cout << "init motors" << std::endl; + + // Initialize all Joints + joints.at(0) = + std::make_unique(std::move(elbowPitch_joint), n); + joints.at(1) = std::make_unique(std::move(elbowRoll_joint), n); + joints.at(2) = std::make_unique(std::move(shoulder_joint), n); + joints.at(3) = std::make_unique(std::move(turntable_joint), n); + joints.at(4) = std::make_unique( + std::move(wristPitch_joint), std::move(wristRoll_link), n, + "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", + "/control/arm/21/"); + std::cout << "init joints" << std::endl; + + // Initialize the Action Server + Server server(n, "/arm_controller/follow_joint_trajectory", + boost::bind(&execute, _1, &server), false); + // Start the Action Server + server.start(); + std::cout << "server started" << std::endl; + + enableServiceServer = n.advertiseService( + "start_IK", + static_cast>( + [](std_srvs::Trigger::Request &req, + std_srvs::Trigger::Response &res) -> bool { + IKEnabled = true; + res.message = "Arm IK Enabled"; + res.success = static_cast(true); + return true; + })); + + enableServiceClient = + n.serviceClient("PLACEHOLDER_NAME"); + + std::cout << "entering ROS spin..." << std::endl; + // ROS spin for communication with other nodes + ros::spin(); + // Return 0 on exit (successful exit) + return 0; } diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp index de45e748..b6ecd717 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ b/src/wr_control_drive_arm/src/ArmMotor.cpp @@ -7,8 +7,8 @@ #include "ArmMotor.hpp" #include #include -#include #include +#include /// Allow for referencing the UInt32 message type easier using Std_UInt32 = std_msgs::UInt32::ConstPtr; @@ -17,47 +17,50 @@ using Std_Bool = std_msgs::Bool::ConstPtr; auto ArmMotor::corrMod(double i, double j) -> double { // Stem i%j by j, which in modular arithmetic is the same as adding 0. - return std::fmod(std::fmod(std::abs(j)*i/j,std::abs(j))+j,std::abs(j)); + return std::fmod(std::fmod(std::abs(j) * i / j, std::abs(j)) + j, std::abs(j)); } /// Currently consistent with the rad->enc equation as specified here. -auto ArmMotor::radToEnc(double rads) const -> uint32_t{ - double remappedEnc = ArmMotor::corrMod(rads, 2 * M_PI)/(2 * M_PI); +auto ArmMotor::radToEnc(double rads) const -> uint32_t { + double remappedEnc = ArmMotor::corrMod(rads, 2 * M_PI) / (2 * M_PI); return ArmMotor::corrMod((this->COUNTS_PER_ROTATION * remappedEnc) + this->ENCODER_OFFSET, abs(this->COUNTS_PER_ROTATION)); } -auto ArmMotor::encToRad(uint32_t enc) const -> double{ +auto ArmMotor::encToRad(uint32_t enc) const -> double { double remappedEnc = ArmMotor::corrMod(static_cast(enc - this->ENCODER_OFFSET), abs(static_cast(this->COUNTS_PER_ROTATION))) / this->COUNTS_PER_ROTATION; - return ArmMotor::corrMod( remappedEnc * 2 * M_PI + M_PI, 2 * M_PI) - M_PI; + return ArmMotor::corrMod(remappedEnc * 2 * M_PI + M_PI, 2 * M_PI) - M_PI; } /// Currently consistent with the enc->rad equation as specified here. -auto ArmMotor::getRads() const -> double{ +auto ArmMotor::getRads() const -> double { return ArmMotor::encToRad(this->getEncoderCounts()); } -void ArmMotor::storeEncoderVals(const Std_UInt32 &msg){ +void ArmMotor::storeEncoderVals(const Std_UInt32 &msg) { // Store the message value in this ArmMotor's encoderVal variable this->encoderVal = msg->data; - + // Send feedback std_msgs::Float64 feedbackMsg; feedbackMsg.data = ArmMotor::encToRad(msg->data); - this->feedbackPub.publish(feedbackMsg); + if (!readOnly) + this->feedbackPub.publish(feedbackMsg); - if(this->currState == MotorState::RUN_TO_TARGET){ + if (this->currState == MotorState::RUN_TO_TARGET) { // std::cout << "[2] motor " << motorName << " position " << (hasReachedTarget(this->target) ? "at target " : "not at target ") << this->target << ":" << this->encoderVal << std::endl; - if(hasReachedTarget(this->target)){ + if (hasReachedTarget(this->target)) { // std::cout << "[1] stop motor" << std::endl; this->setPower(0.F, MotorState::STOP); } } } -void ArmMotor::redirectPowerOutput(const Std_Float64 &msg){ +void ArmMotor::redirectPowerOutput(const Std_Float64 &msg) { // Set the speed to be the contained data - if(abs(msg->data) > 1) std::cout << "Received power " << msg->data << " from PID for motor " << motorName << std::endl; - if(this->getMotorState() == MotorState::RUN_TO_TARGET) this->setPower(static_cast(msg->data) * this->maxPower, MotorState::RUN_TO_TARGET); + if (abs(msg->data) > 1) + std::cout << "Received power " << msg->data << " from PID for motor " << motorName << std::endl; + if (this->getMotorState() == MotorState::RUN_TO_TARGET) + this->setPower(static_cast(msg->data) * this->maxPower, MotorState::RUN_TO_TARGET); } void ArmMotor::storeStallStatus(const Std_Bool &msg) { @@ -79,21 +82,24 @@ ArmMotor::ArmMotor( unsigned int motorID, int64_t countsPerRotation, int64_t offset, - ros::NodeHandle &n -) : COUNTS_PER_ROTATION{countsPerRotation}, - ENCODER_BOUNDS{0, std::abs(countsPerRotation)}, - ENCODER_OFFSET{offset}, - motorName{std::move(motor_name)}, - controllerID{controllerID}, - motorID{motorID}, - currState{MotorState::STOP}, - power{0.F}, - maxPower{0.F}, - encoderVal{static_cast(offset)} { - + ros::NodeHandle &n, + bool readOnly) : COUNTS_PER_ROTATION{countsPerRotation}, + ENCODER_BOUNDS{0, std::abs(countsPerRotation)}, + ENCODER_OFFSET{offset}, + motorName{std::move(motor_name)}, + controllerID{controllerID}, + motorID{motorID}, + currState{MotorState::STOP}, + power{0.F}, + maxPower{0.F}, + encoderVal{static_cast(offset)}, + readOnly{readOnly} { + // Check validity of WRoboclaw and motor IDs - if(controllerID > 3) throw std::invalid_argument{std::string{"Controller ID "} + std::to_string(controllerID) + "is only valid on [0,3]"}; - if(motorID > 1) throw std::invalid_argument{std::string{"Motor ID "} + std::to_string(motorID) + " is only valid on [0,1]"}; + if (controllerID > 3) + throw std::invalid_argument{std::string{"Controller ID "} + std::to_string(controllerID) + "is only valid on [0,3]"}; + if (motorID > 1) + throw std::invalid_argument{std::string{"Motor ID "} + std::to_string(motorID) + " is only valid on [0,1]"}; // Create the topic string prefix for WRoboclaw controllers std::string tpString = std::string{"/hsi/roboclaw/aux"} + std::to_string(controllerID); @@ -101,25 +107,27 @@ ArmMotor::ArmMotor( // Create the appropriate encoder-reading and speed-publishing subscribers and advertisers, respectfully this->encRead = n.subscribe(tpString + "/enc/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE, &ArmMotor::storeEncoderVals, this); - this->speedPub = n.advertise(tpString + "/cmd/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE); - this->targetPub = n.advertise(controlString + "/setpoint", ArmMotor::MESSAGE_CACHE_SIZE); - this->feedbackPub = n.advertise(controlString + "/feedback", ArmMotor::MESSAGE_CACHE_SIZE); + if (!readOnly) { + this->speedPub = n.advertise(tpString + "/cmd/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE); + this->targetPub = n.advertise(controlString + "/setpoint", ArmMotor::MESSAGE_CACHE_SIZE); + this->feedbackPub = n.advertise(controlString + "/feedback", ArmMotor::MESSAGE_CACHE_SIZE); + } this->outputRead = n.subscribe(controlString + "/output", ArmMotor::MESSAGE_CACHE_SIZE, &ArmMotor::redirectPowerOutput, this); this->stallRead = n.subscribe(tpString + "/curr/over_lim/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE, &ArmMotor::storeStallStatus, this); std::cout << this->motorName << ": " << this->COUNTS_PER_ROTATION << std::endl; } -auto ArmMotor::getEncoderCounts() const -> uint32_t{ +auto ArmMotor::getEncoderCounts() const -> uint32_t { return this->encoderVal; } -void ArmMotor::runToTarget(uint32_t targetCounts, float power){ +void ArmMotor::runToTarget(uint32_t targetCounts, float power) { // std::cout << "run to enc: " << targetCounts << std::endl; this->runToTarget(targetCounts, power, false); } -auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool{ +auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool { // std::cout << "TOLERANCE: " << tolerance << std::endl; // Compute the upper and lower bounds in the finite encoder space int32_t lBound = ArmMotor::corrMod(static_cast(targetCounts - tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); @@ -129,86 +137,91 @@ auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const // std::cout << "POSITION RAW: " << encToRad(getEncoderCounts()) << "/" << getEncoderCounts() << std::endl; // std::cout << "POSITION: " << encToRad(position) << "/" << position << std::endl; // If the computed lower bound is lower than the upper bound, perform the computation normally - if(lBound < uBound) - return position <= uBound && position >=lBound; + if (lBound < uBound) + return position <= uBound && position >= lBound; // Otherwise, check if the value is outside either bound and negate the response return position <= uBound || position >= lBound; } /// Current tolerance is ±0.1 degree w.r.t. the current number of counts per rotation -auto ArmMotor::hasReachedTarget(uint32_t targetCounts) const -> bool{ +auto ArmMotor::hasReachedTarget(uint32_t targetCounts) const -> bool { auto tol = ArmMotor::TOLERANCE_RATIO * static_cast(std::abs(this->COUNTS_PER_ROTATION)); - return ArmMotor::hasReachedTarget(targetCounts, std::max(1.0,tol)); + return ArmMotor::hasReachedTarget(targetCounts, std::max(1.0, tol)); } -auto ArmMotor::getMotorState() const -> MotorState{ +auto ArmMotor::getMotorState() const -> MotorState { return this->currState; } -void ArmMotor::setPower(float power){ +void ArmMotor::setPower(float power) { this->setPower(power, power == 0.F ? MotorState::STOP : MotorState::MOVING); } /// This method auto-publishes the speed command to the WRoboclaws -void ArmMotor::setPower(float power, MotorState state){ +void ArmMotor::setPower(float power, MotorState state) { // Check the bounds of the parameter - if(abs(power) > 1) throw std::invalid_argument{std::string{"Power "} + std::to_string(power) + " is not on the interval [-1, 1]"}; - - // Set up and send the speed message - this->power = power; - this->powerMsg.data = power * INT16_MAX; - this->speedPub.publish(this->powerMsg); - // Update the cur.nt motor state based on the power command input - this->currState = state; + if (abs(power) > 1) + throw std::invalid_argument{std::string{"Power "} + std::to_string(power) + " is not on the interval [-1, 1]"}; + + if (!readOnly) { + // Set up and send the speed message + this->power = power; + this->powerMsg.data = power * INT16_MAX; + this->speedPub.publish(this->powerMsg); + // Update the cur.nt motor state based on the power command input + this->currState = state; + } } -void ArmMotor::runToTarget(uint32_t targetCounts, float power, bool block){ - this->target = targetCounts; +void ArmMotor::runToTarget(uint32_t targetCounts, float power, bool block) { + this->target = targetCounts; this->maxPower = abs(power); // If we are not at our target... - if(!this->hasReachedTarget(targetCounts)){ + if (!this->hasReachedTarget(targetCounts)) { // std::cout << "has not reached target" << std::endl; // Set the power in the correct direction and continue running to the target this->currState = MotorState::RUN_TO_TARGET; std_msgs::Float64 setpointMsg; setpointMsg.data = ArmMotor::encToRad(targetCounts); - this->targetPub.publish(setpointMsg); + if (!readOnly) + this->targetPub.publish(setpointMsg); // long int direction = targetCounts - this->getEncoderCounts(); // power = abs(power) * (corrMod(direction, ((long int)this->COUNTS_PER_ROTATION)) < corrMod(-direction, ((long int)this->COUNTS_PER_ROTATION)) ? 1 : -1); // this->setPower(power, MotorState::RUN_TO_TARGET); - // Otherwise, stop the motor + // Otherwise, stop the motor } else { // std::cout << "has reached target" << std::endl; this->setPower(0.F, MotorState::STOP); } // If this is a blocking call... - if(block){ + if (block) { // Wait until the motor has reached the target, then stop - while(!this->hasReachedTarget(targetCounts)); + while (!this->hasReachedTarget(targetCounts)) + ; this->setPower(0.F, MotorState::RUN_TO_TARGET); } } -void ArmMotor::runToTarget(double rads, float power){ +void ArmMotor::runToTarget(double rads, float power) { // std::cout << "run to target: " << rads << ":" << this->radToEnc(rads) << ":" << this->getEncoderCounts() << std::endl; - + runToTarget(this->radToEnc(rads), power, false); } -auto ArmMotor::getMotorName() const -> std::string{ +auto ArmMotor::getMotorName() const -> std::string { return this->motorName; } -auto ArmMotor::getMotorID() const -> unsigned int{ +auto ArmMotor::getMotorID() const -> unsigned int { return this->motorID; } -auto ArmMotor::getControllerID() const -> unsigned int{ +auto ArmMotor::getControllerID() const -> unsigned int { return this->controllerID; } -auto ArmMotor::getPower() const -> float{ +auto ArmMotor::getPower() const -> float { return this->power; } \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/ArmMotor.hpp b/src/wr_control_drive_arm/src/ArmMotor.hpp index ba4d2120..9ad871c2 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.hpp +++ b/src/wr_control_drive_arm/src/ArmMotor.hpp @@ -4,20 +4,20 @@ * @brief Header file of the ArmMotor class * @date 2021-04-05 */ - -#include + #include "ros/ros.h" -#include "std_msgs/UInt32.h" -#include "std_msgs/Int16.h" -#include "std_msgs/Float64.h" #include "std_msgs/Bool.h" +#include "std_msgs/Float64.h" +#include "std_msgs/Int16.h" +#include "std_msgs/UInt32.h" #include +#include #include /** * @brief An enumeration of states for a motor to be in. */ -enum class MotorState{ +enum class MotorState { /// A Motor is stopped (not moving, 0 power command) STOP, /// A Motor is moving (non-0 power command) @@ -27,216 +27,233 @@ enum class MotorState{ /// A Motor is stalling (over safety current limit) STALLING }; + /** * @brief A way to control arm motors with WRoboclaw */ -class ArmMotor{ - private: - /// Time tolerance of over-current detection before a stall fault is triggered - static constexpr float STALL_THRESHOLD_TIME = 0.5; - /// Tolerance ratio w.r.t the counts per rotation for encoder run-to-position motion - static constexpr double TOLERANCE_RATIO = 0.1/360; - /// Size of ROS Topic message caches - static constexpr uint32_t MESSAGE_CACHE_SIZE = 10; - /// The number of encoder counts per rotation - int64_t const COUNTS_PER_ROTATION; - /// The upper and lower bounds of encoder rotation for absolute encoders (index 0 is lower, index 1 is upper) - std::array const ENCODER_BOUNDS; - /// zero position of motor - int64_t const ENCODER_OFFSET; - /// The current state of the motor - std::atomic currState; - /// The joint name of the current motor - std::string motorName; - /// The ID of the WRoboclaw controller - unsigned int controllerID; - /// The ID of the motor within the WRoboclaw controller - unsigned int motorID; - /// The current encoder value - uint32_t encoderVal; - /// Target encoder counts for run to target - uint32_t target; - /// The ROS Subscriber that reads the encoders - ros::Subscriber encRead; - /// The ROS Publisher that sets the encoder targets - ros::Publisher targetPub; - /// The ROS Publisher that sets encoder feedback data - ros::Publisher feedbackPub; - /// The ROS Subscriber that reads controlled output data - ros::Subscriber outputRead; - /// The ROS Publisher that publishes motor speed commands - ros::Publisher speedPub; - /// The most recent power message sent - std_msgs::Int16 powerMsg; - /// The ROS Subscriber that reads stall status data - ros::Subscriber stallRead; - /// The time when the motor began stalling - ros::Time beginStallTime; - /// Motor power - float power; - /// Maximum absolute motor power in RUN_TO_POSITION mode. - std::atomic maxPower; - - /** - * @brief A static conversion from radians to encoder counts - * - * @param rad The input number of radians - * @return uint32_t The corresponding encoder count bounded by ENCODER_BOUNDS - */ - auto radToEnc(double rad) const -> uint32_t; - - /** - * @brief A static conversion from encoder counts to radians - * - * @param enc The input number of encoder counts - * @return double The corresponding radian measure - */ - auto encToRad(uint32_t enc) const -> double; - - /** - * @brief Subscriber callback for encRead, captures the encoder value of the current motor - * - * @param msg The encoder value message as captured by encRead - */ - void storeEncoderVals(const std_msgs::UInt32::ConstPtr& msg); - - /** - * @brief Subscriber callback for outputRead, captures the PID output and sets the speed directly - * - * @param msg The PID output as captured by outputRead - */ - void redirectPowerOutput(const std_msgs::Float64::ConstPtr& msg); - - /** - * @brief Subscriber callback for stallRead, captures the stall status of the current motor - * - * @param msg The stall status of the current motor - */ - void storeStallStatus(const std_msgs::Bool::ConstPtr& msg); - - void setPower(float power, MotorState state); - - /** - * @brief Performs Euclidean correct modulus between two inputs of the same type - * - * @param i The dividend of the modulus - * @param j The divisor of the modulus - * @return double The Euclidean-correct remainder bounded on [0, j) - */ - static auto corrMod(double i, double j) -> double; - - public: - /** - * @brief Constructs a new ArmMotor - * - * @param motorName The joint name of the motor - * @param controllerID The WRoboclaw controller ID for this motor - * @param motorID The motor ID within its WRoboclaw controller - * @param n A NodeHandle reference to the constructing Node - */ - ArmMotor(std::string motorName, unsigned int controllerID, unsigned int motorID, int64_t countsPerRotation, int64_t offset, ros::NodeHandle &n); - - /** - * @brief Gets the encoder value of the motor - * - * @return uint32_t The current encoder value of the motor - */ - auto getEncoderCounts() const -> uint32_t; - - /** - * @brief Sends the motor to run to a target encoder value at a given power without blocking - * - * @param targetCounts The target encoder value for the motor - * @param power The power to move the motor at (Bounded between [-1, 1]) - */ - void runToTarget(uint32_t targetCounts, float power); - - /** - * @brief Sends the motor to run to a target encoder value at a given power - * - * @param targetCounts The target encoder value for the motor - * @param power The power to move the motor at (Bounded between [-1, 1]) - * @param block Specifies whether or not this action should block until it is complete - * @return True if the motor had stalled, and false otherwise - */ - void runToTarget(uint32_t targetCounts, float power, bool block); - - /** - * @brief Sends the motor to run to a specified position at a given power - * - * @param rads The position to send the motor to (specified in radians) - * @param power The power to move the motor at (Bounded between [-1, 1]) - * @return True if the motor had stalled, and false otherwise - */ - void runToTarget(double rads, float power); - - /** - * @brief Get the current state of the ArmMotor - * - * @return MotorState The current state of the ArmMotor - */ - auto getMotorState() const -> MotorState; - - /** - * @brief Set the motor power - * - * @param power The power to set the motor at (Bounded between [-1, 1]) - */ - void setPower(float power); - - /** - * @brief Get the radian measure of the current motor - * - * @return double The radian measure of the current motor's position - */ - auto getRads() const -> double; - - /** - * @brief Get the name of the ArmMotor - * - * @return std::string The name of the ArmMotor - */ - auto getMotorName() const -> std::string; - - /** - * @brief Get the name of the ArmMotor - * - * @return std::string The controller ID of the ArmMotor - */ - auto getControllerID() const -> unsigned int; - - /** - * @brief Get the name of the ArmMotor - * - * @return std::string The motor ID of the ArmMotor - */ - auto getMotorID() const -> unsigned int; - - - /** - * @brief Checks if the motor is currently within a pre-specified tolerance of a target - * - * @param targetCounts The target to test against - * @return true The motor was within the target tolerance - * @return false The motor was outside of the target tolerance - */ - auto hasReachedTarget(uint32_t targetCounts) const -> bool; - - /** - * @brief Checks if the motor is currently within a given tolerance of a target - * - * @param targetCounts The target to test against - * @param tolerance The tolerance to give when testing the target - * @return true The motor was within the target tolerance - * @return false The motor was outside the target tolerance - */ - auto hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool; - - /** - * @brief Get the most recently set motor power - * - * @return float Last motor power setting - */ - auto getPower() const -> float; -}; +class ArmMotor { +private: + /// Time tolerance of over-current detection before a stall fault is + /// triggered + static constexpr float STALL_THRESHOLD_TIME = 0.5; + /// Tolerance ratio w.r.t the counts per rotation for encoder + /// run-to-position motion + static constexpr double TOLERANCE_RATIO = 0.1 / 360; + /// Size of ROS Topic message caches + static constexpr uint32_t MESSAGE_CACHE_SIZE = 10; + /// The number of encoder counts per rotation + int64_t const COUNTS_PER_ROTATION; + /// The upper and lower bounds of encoder rotation for absolute encoders + /// (index 0 is lower, index 1 is upper) + std::array const ENCODER_BOUNDS; + /// zero position of motor + int64_t const ENCODER_OFFSET; + /// The current state of the motor + std::atomic currState; + /// The joint name of the current motor + std::string motorName; + /// The ID of the WRoboclaw controller + unsigned int controllerID; + /// The ID of the motor within the WRoboclaw controller + unsigned int motorID; + /// The current encoder value + uint32_t encoderVal; + /// Target encoder counts for run to target + uint32_t target; + /// The ROS Subscriber that reads the encoders + ros::Subscriber encRead; + /// The ROS Publisher that sets the encoder targets + ros::Publisher targetPub; + /// The ROS Publisher that sets encoder feedback data + ros::Publisher feedbackPub; + /// The ROS Subscriber that reads controlled output data + ros::Subscriber outputRead; + /// The ROS Publisher that publishes motor speed commands + ros::Publisher speedPub; + /// The most recent power message sent + std_msgs::Int16 powerMsg; + /// The ROS Subscriber that reads stall status data + ros::Subscriber stallRead; + /// The time when the motor began stalling + ros::Time beginStallTime; + /// Motor power + float power; + /// Maximum absolute motor power in RUN_TO_POSITION mode. + std::atomic maxPower; + /// Whether or not this motor is read-only + bool readOnly; + + /** + * @brief A static conversion from radians to encoder counts + * + * @param rad The input number of radians + * @return uint32_t The corresponding encoder count bounded by + * ENCODER_BOUNDS + */ + auto radToEnc(double rad) const -> uint32_t; + + /** + * @brief A static conversion from encoder counts to radians + * + * @param enc The input number of encoder counts + * @return double The corresponding radian measure + */ + auto encToRad(uint32_t enc) const -> double; + + /** + * @brief Subscriber callback for encRead, captures the encoder value of the + * current motor + * + * @param msg The encoder value message as captured by encRead + */ + void storeEncoderVals(const std_msgs::UInt32::ConstPtr &msg); + + /** + * @brief Subscriber callback for outputRead, captures the PID output and + * sets the speed directly + * + * @param msg The PID output as captured by outputRead + */ + void redirectPowerOutput(const std_msgs::Float64::ConstPtr &msg); + + /** + * @brief Subscriber callback for stallRead, captures the stall status of + * the current motor + * + * @param msg The stall status of the current motor + */ + void storeStallStatus(const std_msgs::Bool::ConstPtr &msg); + void setPower(float power, MotorState state); + + /** + * @brief Performs Euclidean correct modulus between two inputs of the same + * type + * + * @param i The dividend of the modulus + * @param j The divisor of the modulus + * @return double The Euclidean-correct remainder bounded on [0, j) + */ + static auto corrMod(double i, double j) -> double; + +public: + /** + * @brief Constructs a new ArmMotor + * + * @param motorName The joint name of the motor + * @param controllerID The WRoboclaw controller ID for this motor + * @param motorID The motor ID within its WRoboclaw controller + * @param n A NodeHandle reference to the constructing Node + * @param readOnly whether this motor will inhibit control messages + */ + ArmMotor(std::string motorName, unsigned int controllerID, + unsigned int motorID, int64_t countsPerRotation, int64_t offset, + ros::NodeHandle &n, bool readOnly = false); + + /** + * @brief Gets the encoder value of the motor + * + * @return uint32_t The current encoder value of the motor + */ + auto getEncoderCounts() const -> uint32_t; + + /** + * @brief Sends the motor to run to a target encoder value at a given power + * without blocking + * + * @param targetCounts The target encoder value for the motor + * @param power The power to move the motor at (Bounded between [-1, 1]) + */ + void runToTarget(uint32_t targetCounts, float power); + + /** + * @brief Sends the motor to run to a target encoder value at a given power + * + * @param targetCounts The target encoder value for the motor + * @param power The power to move the motor at (Bounded between [-1, 1]) + * @param block Specifies whether or not this action should block until it + * is complete + * @return True if the motor had stalled, and false otherwise + */ + void runToTarget(uint32_t targetCounts, float power, bool block); + + /** + * @brief Sends the motor to run to a specified position at a given power + * + * @param rads The position to send the motor to (specified in radians) + * @param power The power to move the motor at (Bounded between [-1, 1]) + * @return True if the motor had stalled, and false otherwise + */ + void runToTarget(double rads, float power); + + /** + * @brief Get the current state of the ArmMotor + * + * @return MotorState The current state of the ArmMotor + */ + auto getMotorState() const -> MotorState; + + /** + * @brief Set the motor power + * + * @param power The power to set the motor at (Bounded between [-1, 1]) + */ + void setPower(float power); + + /** + * @brief Get the radian measure of the current motor + * + * @return double The radian measure of the current motor's position + */ + auto getRads() const -> double; + + /** + * @brief Get the name of the ArmMotor + * + * @return std::string The name of the ArmMotor + */ + auto getMotorName() const -> std::string; + + /** + * @brief Get the name of the ArmMotor + * + * @return std::string The controller ID of the ArmMotor + */ + auto getControllerID() const -> unsigned int; + + /** + * @brief Get the name of the ArmMotor + * + * @return std::string The motor ID of the ArmMotor + */ + auto getMotorID() const -> unsigned int; + + /** + * @brief Checks if the motor is currently within a pre-specified tolerance + * of a target + * + * @param targetCounts The target to test against + * @return true The motor was within the target tolerance + * @return false The motor was outside of the target tolerance + */ + auto hasReachedTarget(uint32_t targetCounts) const -> bool; + + /** + * @brief Checks if the motor is currently within a given tolerance of a + * target + * + * @param targetCounts The target to test against + * @param tolerance The tolerance to give when testing the target + * @return true The motor was within the target tolerance + * @return false The motor was outside the target tolerance + */ + auto hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const + -> bool; + + /** + * @brief Get the most recently set motor power + * + * @return float Last motor power setting + */ + auto getPower() const -> float; +}; diff --git a/src/wr_control_drive_arm/src/JointStatePublisher.cpp b/src/wr_control_drive_arm/src/JointStatePublisher.cpp index b6d47251..3638c4ff 100644 --- a/src/wr_control_drive_arm/src/JointStatePublisher.cpp +++ b/src/wr_control_drive_arm/src/JointStatePublisher.cpp @@ -3,32 +3,32 @@ * @author Ben Nowotny * @author Jack Zautner * @brief The executable file to run the joint state publisher - * @date 2022-12-05 + * @date 2022-12-05 */ #include "XmlRpcValue.h" +#include "DifferentialJoint.hpp" +#include "SimpleJoint.hpp" +#include "ros/console.h" #include "ros/ros.h" -#include #include -#include -#include -#include #include -#include -#include #include +#include +#include #include +#include +#include +#include #include -#include "SimpleJoint.hpp" -#include "DifferentialJoint.hpp" -#include "ros/console.h" +#include using XmlRpc::XmlRpcValue; /** * @brief Nessage cache size of publisher */ -constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; +constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; /** * @brief Period between timer callback @@ -46,33 +46,33 @@ std::array, NUM_JOINTS> joints; */ ros::Publisher jointStatePublisher; -void publishJointStates(const ros::TimerEvent &event){ - std::vector names; - std::vector positions; - sensor_msgs::JointState js_msg; +void publishJointStates(const ros::TimerEvent &event) { + std::vector names; + std::vector positions; + sensor_msgs::JointState js_msg; - for(const auto &joint : joints){ - for(int i = 0; i < joint->getDegreesOfFreedom(); i++){ - names.push_back(joint->getMotor(i)->getMotorName()); - positions.push_back(joint->getMotor(i)->getRads()); + for (const auto &joint : joints) { + for (int i = 0; i < joint->getDegreesOfFreedom(); i++) { + names.push_back(joint->getMotor(i)->getMotorName()); + positions.push_back(joint->getMotor(i)->getRads()); + } } - } - js_msg.name = names; - js_msg.position = positions; - js_msg.header.stamp = ros::Time::now(); - // Publish the Joint State message - jointStatePublisher.publish(js_msg); + js_msg.name = names; + js_msg.position = positions; + js_msg.header.stamp = ros::Time::now(); + // Publish the Joint State message + jointStatePublisher.publish(js_msg); } /** * @brief The main executable method of the node. Starts the ROS node - * + * * @param argc The number of program arguments * @param argv The given program arguments * @return int The status code on exiting the program */ -auto main(int argc, char** argv) -> int { +auto main(int argc, char **argv) -> int { std::cout << "start main" << std::endl; // Initialize the current node as JointStatePublisherApplication @@ -85,12 +85,12 @@ auto main(int argc, char** argv) -> int { pn.getParam("encoder_parameters", encParams); // Initialize all motors with their MoveIt name, WRoboclaw initialization, and reference to the current node - auto elbowPitch_joint = std::make_unique("elbowPitch_joint", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n); - auto elbowRoll_joint = std::make_unique("elbowRoll_joint", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n); - auto shoulder_joint = std::make_unique("shoulder_joint", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n); - auto turntable_joint = std::make_unique("turntable_joint", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n); - auto wristPitch_joint = std::make_unique("wristPitch_joint", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n); - auto wristRoll_link = std::make_unique("wristRoll_link", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n); + auto elbowPitch_joint = std::make_unique("elbowPitch_joint", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n, true); + auto elbowRoll_joint = std::make_unique("elbowRoll_joint", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n, true); + auto shoulder_joint = std::make_unique("shoulder_joint", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n, true); + auto turntable_joint = std::make_unique("turntable_joint", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n, true); + auto wristPitch_joint = std::make_unique("wristPitch_joint", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n, true); + auto wristRoll_link = std::make_unique("wristRoll_link", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n, true); std::cout << "init motors" << std::endl; // Initialize all Joints @@ -100,7 +100,7 @@ auto main(int argc, char** argv) -> int { joints.at(3) = std::make_unique(std::move(turntable_joint), n); joints.at(4) = std::make_unique(std::move(wristPitch_joint), std::move(wristRoll_link), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); std::cout << "init joints" << std::endl; - + // Initialize the Joint State Data Publisher jointStatePublisher = n.advertise("/joint_states", MESSAGE_CACHE_SIZE); diff --git a/test_arm_control_stack.sh b/test_arm_control_stack.sh index 3238d1ac..af265954 100755 --- a/test_arm_control_stack.sh +++ b/test_arm_control_stack.sh @@ -11,7 +11,7 @@ cd $ROOT_DIR #done #rm ./out.temp; export WROVER_LOCAL=true -export WROVER_HW=REAL +export WROVER_HW=MOCK MOTOR_TO_INSPECT=11 # (sleep 2 && rqt_plot /control/arm/$MOTOR_TO_INSPECT/output /control/arm/$MOTOR_TO_INSPECT/setpoint /control/arm/$MOTOR_TO_INSPECT/feedback) & #/hsi/roboclaw/aux1/cmd/left roslaunch wr_entry_point mock_arm.launch From ad6629c0a2a98db59b90d59435b0b197a3b12e7d Mon Sep 17 00:00:00 2001 From: WR-BaseStation Date: Mon, 23 Jan 2023 19:39:57 -0600 Subject: [PATCH 19/33] Fixing controller logic, issue in differential joint marked --- src/wr_control_drive_arm/launch/actionserver.launch | 2 +- .../src/ArmControlActionServer.cpp | 13 +++++++------ src/wr_control_drive_arm/src/ArmMotor.cpp | 12 +++++++----- src/wr_control_drive_arm/src/DifferentialJoint.cpp | 1 + src/wr_entry_point/launch/comp/comp_init.launch | 4 ++-- src/wr_entry_point/launch/test/mock_arm.launch | 4 ++-- src/wroboarm_23/config/joint_limits.yaml | 8 ++++---- 7 files changed, 24 insertions(+), 20 deletions(-) diff --git a/src/wr_control_drive_arm/launch/actionserver.launch b/src/wr_control_drive_arm/launch/actionserver.launch index 115c85dd..4bf4ebe7 100644 --- a/src/wr_control_drive_arm/launch/actionserver.launch +++ b/src/wr_control_drive_arm/launch/actionserver.launch @@ -2,7 +2,7 @@ - + configSetpoint(i, currTargetPosition.positions[currItr], velocity); currItr++; @@ -136,7 +136,7 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, } // While the current position is not complete yet... - while (!hasPositionFinished) { + while (!hasPositionFinished && ros::ok()) { // Assume the current action is done until proven otherwise hasPositionFinished = true; // Create the Joint State message for the current update cycle @@ -181,6 +181,7 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, hasPositionFinished &= joint->getMotor(k)->getMotorState() == MotorState::STOP; + std::cout << joint->getMotor(k)->getMotorName() << " state: " << (joint->getMotor(k)->getMotorState() == MotorState::STOP) << std::endl; } // DEBUGGING OUTPUT: Print each motor's name, radian // position, encoder position, and power diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp index b6ecd717..10f25e05 100644 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ b/src/wr_control_drive_arm/src/ArmMotor.cpp @@ -146,7 +146,7 @@ auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const /// Current tolerance is ±0.1 degree w.r.t. the current number of counts per rotation auto ArmMotor::hasReachedTarget(uint32_t targetCounts) const -> bool { auto tol = ArmMotor::TOLERANCE_RATIO * static_cast(std::abs(this->COUNTS_PER_ROTATION)); - return ArmMotor::hasReachedTarget(targetCounts, std::max(1.0, tol)); + return ArmMotor::hasReachedTarget(targetCounts, std::max(10.0, tol)); } auto ArmMotor::getMotorState() const -> MotorState { @@ -176,15 +176,17 @@ void ArmMotor::setPower(float power, MotorState state) { void ArmMotor::runToTarget(uint32_t targetCounts, float power, bool block) { this->target = targetCounts; this->maxPower = abs(power); + + std_msgs::Float64 setpointMsg; + setpointMsg.data = ArmMotor::encToRad(targetCounts); + if (!readOnly) + this->targetPub.publish(setpointMsg); + // If we are not at our target... if (!this->hasReachedTarget(targetCounts)) { // std::cout << "has not reached target" << std::endl; // Set the power in the correct direction and continue running to the target this->currState = MotorState::RUN_TO_TARGET; - std_msgs::Float64 setpointMsg; - setpointMsg.data = ArmMotor::encToRad(targetCounts); - if (!readOnly) - this->targetPub.publish(setpointMsg); // long int direction = targetCounts - this->getEncoderCounts(); // power = abs(power) * (corrMod(direction, ((long int)this->COUNTS_PER_ROTATION)) < corrMod(-direction, ((long int)this->COUNTS_PER_ROTATION)) ? 1 : -1); diff --git a/src/wr_control_drive_arm/src/DifferentialJoint.cpp b/src/wr_control_drive_arm/src/DifferentialJoint.cpp index 85c3c1c7..809a5772 100644 --- a/src/wr_control_drive_arm/src/DifferentialJoint.cpp +++ b/src/wr_control_drive_arm/src/DifferentialJoint.cpp @@ -19,6 +19,7 @@ DifferentialJoint::DifferentialJoint(std::unique_ptr leftMotor, std::u this->motors.at(0) = {std::move(leftMotor), 0, 0, "", "", false}; this->motors.at(1) = {std::move(rightMotor), 0, 0, "", "", false}; + // TODO: This should NOT be bypassing the motors in handling PID. This should do frame conversions and pass the results into the motors to handle the actual ROS comms this->pitchOutputSubscriber = n.subscribe(pitchTopicName + "/output", MESSAGE_CACHE_SIZE, &DifferentialJoint::handoffPitchOutput, this); this->rollOutputSubscriber = n.subscribe(rollTopicName + "/output", MESSAGE_CACHE_SIZE, &DifferentialJoint::handoffRollOutput, this); this->leftOutputPublisher = n.advertise(leftTopicName + "/output", MESSAGE_CACHE_SIZE); diff --git a/src/wr_entry_point/launch/comp/comp_init.launch b/src/wr_entry_point/launch/comp/comp_init.launch index ea3bb01d..36f80295 100644 --- a/src/wr_entry_point/launch/comp/comp_init.launch +++ b/src/wr_entry_point/launch/comp/comp_init.launch @@ -4,9 +4,9 @@ - + - + diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index 67744854..67abb1df 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -2,7 +2,7 @@ - + @@ -17,5 +17,5 @@ - + diff --git a/src/wroboarm_23/config/joint_limits.yaml b/src/wroboarm_23/config/joint_limits.yaml index 2454284c..1935df40 100644 --- a/src/wroboarm_23/config/joint_limits.yaml +++ b/src/wroboarm_23/config/joint_limits.yaml @@ -34,8 +34,8 @@ joint_limits: max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 - max_position: !radians pi / 2 - min_position: !radians 0 + max_position: !radians pi + min_position: !radians -pi wristPitch_joint: has_velocity_limits: true max_velocity: 10 @@ -48,5 +48,5 @@ joint_limits: max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 - max_position: !radians pi / 2 - min_position: !radians -pi / 2 \ No newline at end of file + max_position: !radians pi + min_position: !radians -pi \ No newline at end of file From 3233dd9f0b7c61ba690aebeb5981641030838f12 Mon Sep 17 00:00:00 2001 From: Ben Nowotny Date: Wed, 1 Feb 2023 19:51:02 -0600 Subject: [PATCH 20/33] Adding documentation for new structure --- src/wr_control_drive_arm/structure.wsd | 74 ++++++++++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100755 src/wr_control_drive_arm/structure.wsd diff --git a/src/wr_control_drive_arm/structure.wsd b/src/wr_control_drive_arm/structure.wsd new file mode 100755 index 00000000..4f8addaa --- /dev/null +++ b/src/wr_control_drive_arm/structure.wsd @@ -0,0 +1,74 @@ +@startuml Structure +enum MotorChannel{ + + A + + B +} +class Motor{ + + Motor(string controllerName, Channel motorChannel) + + void setPower(double power) + + bool getOverCurrentStatus() +} + +Motor -> MotorChannel + +class Joint{ + + Joint(String name) + + void setTarget(double target) + + bool hasReachedTarget() + + void stop() +} + +interface JointPositionMonitor{ + + {abstract} virtual double getJointPosition() +} + +class EncoderJointPositionMonitor implements JointPositionMonitor{ + +} + +interface JointToMotorSpeedConverter{ + + {abstract} virtual void setJointSpeed(double speed) +} + +class DirectJointToMotorSpeedConverter implements JointToMotorSpeedConverter{ + +} + +class DifferentialJointToMotorSpeedConverter implements JointToMotorSpeedConverter{ + +} + +@enduml + +@startuml seq + participant ROS + MoveIt -> ActionServer : Sends a motion path + loop For each waypoint in the motion + loop For each joint in the arm + ActionServer -> Joint : Set the next setpoint per joint + Joint -> Joint : Start the execution loop + end + loop While some joint has not reached its setpoint + note over ActionServer : Wait + ROS -> Joint : Kicks off Timer Event + activate Joint + Joint -> "PID Loop" : Feed the setpoint + Joint -> JointPositionMonitor : Ask for the joint position + activate JointPositionMonitor + JointPositionMonitor -> Joint : Sends back joint position + deactivate JointPositionMonitor + Joint -> "PID Loop" : Feed the feedback + deactivate Joint + + "PID Loop" -> Joint : New output available + activate Joint + Joint -> JointToMotorSpeedConverter : Dispatch new speed + activate JointToMotorSpeedConverter + JointToMotorSpeedConverter -> JointToMotorSpeedConverter : Determine hardware speeds + JointToMotorSpeedConverter -> "Motor(s)" : Dispatch hardware speeds + deactivate JointToMotorSpeedConverter + deactivate Joint + end + end + +@enduml From 63de1f4aa167efbb04cde408a4005f465b18b07b Mon Sep 17 00:00:00 2001 From: Ben Nowotny Date: Thu, 2 Feb 2023 12:27:56 -0600 Subject: [PATCH 21/33] Updates to the structure to be better formed and more dynamic with respect to inheritance --- src/wr_control_drive_arm/structure.wsd | 65 ++++++++++++++++++-------- 1 file changed, 45 insertions(+), 20 deletions(-) diff --git a/src/wr_control_drive_arm/structure.wsd b/src/wr_control_drive_arm/structure.wsd index 4f8addaa..ef4f1a40 100755 --- a/src/wr_control_drive_arm/structure.wsd +++ b/src/wr_control_drive_arm/structure.wsd @@ -1,43 +1,66 @@ @startuml Structure -enum MotorChannel{ +enum RoboclawChannel{ + A + B } + +note right of RoboclawChannel::A + Analogous to 'LEFT' +end note + +note right of RoboclawChannel::B + Analogous to 'RIGHT' +end note + class Motor{ - + Motor(string controllerName, Channel motorChannel) + - powerPublisher : ros::Publisher + + + Motor(string controllerName, RoboclawChannel channel) + void setPower(double power) + bool getOverCurrentStatus() } -Motor -> MotorChannel - -class Joint{ - + Joint(String name) - + void setTarget(double target) - + bool hasReachedTarget() - + void stop() -} +Motor --> RoboclawChannel -interface JointPositionMonitor{ - + {abstract} virtual double getJointPosition() +class EncoderJointPositionMonitor { + - encoderSubscriber : ros::Subscriber + - countsPerRotation : const int + - offset : const int + + + EncoderJointPositionMonitor(string controllerName, RoboclawChannel channel, int countsPerRotation, int offset) + - void encoderCallback(std_msgs::Int32) } -class EncoderJointPositionMonitor implements JointPositionMonitor{ +EncoderJointPositionMonitor --> RoboclawChannel +class DirectJointToMotorSpeedConverter { + + DirectJointToMotorSpeedConverter(Motor motor) + + void operator()(double) } -interface JointToMotorSpeedConverter{ - + {abstract} virtual void setJointSpeed(double speed) -} - -class DirectJointToMotorSpeedConverter implements JointToMotorSpeedConverter{ +DirectJointToMotorSpeedConverter "1" --> "1" Motor +class DifferentialJointToMotorSpeedConverter { + + void setPitchSpeed(double) + + void setRollSpeed(double) } -class DifferentialJointToMotorSpeedConverter implements JointToMotorSpeedConverter{ +DifferentialJointToMotorSpeedConverter "1" --> "2" Motor +class Joint{ + + Joint(String name) + + void setTarget(double target) + + bool hasReachedTarget() + + void stop() } +Joint --> EncoderJointPositionMonitor : via function parameter +<> speedConversion +Joint --> speedConversion : via function parameter +speedConversion --> DirectJointToMotorSpeedConverter : as functor +speedConversion --> DifferentialJointToMotorSpeedConverter::setPitchSpeed : as function pointer +speedConversion --> DifferentialJointToMotorSpeedConverter::setRollSpeed : as function pointer + @enduml @startuml seq @@ -55,11 +78,12 @@ class DifferentialJointToMotorSpeedConverter implements JointToMotorSpeedConvert Joint -> "PID Loop" : Feed the setpoint Joint -> JointPositionMonitor : Ask for the joint position activate JointPositionMonitor - JointPositionMonitor -> Joint : Sends back joint position + JointPositionMonitor --> Joint : Sends back joint position deactivate JointPositionMonitor Joint -> "PID Loop" : Feed the feedback deactivate Joint + note left of Joint : Happens asynchonously "PID Loop" -> Joint : New output available activate Joint Joint -> JointToMotorSpeedConverter : Dispatch new speed @@ -70,5 +94,6 @@ class DifferentialJointToMotorSpeedConverter implements JointToMotorSpeedConvert deactivate Joint end end + ActionServer -> MoveIt : Report motion as complete @enduml From 6aaa2061ffd409834d97ad19ad10bb217a4ed05c Mon Sep 17 00:00:00 2001 From: JackZautner <34869117+JackZautner@users.noreply.github.com> Date: Tue, 7 Mar 2023 20:02:44 -0600 Subject: [PATCH 22/33] Feature/arm code refactoring (#33) * Starting to implement new design * Continuing implementation, doing simple parts first to remove big issues * Further implementation * Only Differential stuff and mains left * Up to mains complete * Removing old arm motor files, still in VC for reference * Fixed duplicating copies, need to resolve further * Fixed copying by allowing safer copying. Need to double check path planning * All fixed up. Added test script * Additional changes, some motion planning is possible, need to refine motor/encoder directions * Adding direction multipliers to formalize motor reversal in direct speed converters. Need equivalent for differential speed converters. * Updating constants * First autonomous actions on the arm * Adding legend * Adjusting parameters * Tuning joint limits * Feature/over current fault implementation (#31) * Added functionality to retrieve over current status, updated build settings * Added functionality to stop all joints when a motor is over current * Added implementation for action server to stop when an over current fault is detected * set mock arm launch to launch the mock roboclaw * Added functionality to stop the action server when a motor is over current for too long * Fixed code in compliance with PR * Address fix in Motor.cpp * Corresponding const-change in Motor.hpp * Const-correctness in ArmControlActionServer.cpp --------- Co-authored-by: Ben Nowotny <44074469+bennowotny@users.noreply.github.com> * Removed I terms (need synchronization before we can do that) --------- Co-authored-by: Ben Nowotny Co-authored-by: WR-BaseStation Co-authored-by: Ben Nowotny <44074469+bennowotny@users.noreply.github.com> --- .clang-format | 4 +- src/wr_control_drive_arm/CMakeLists.txt | 286 +++++++------- .../config/arm_motor_PID_mock.yaml | 69 ++-- .../config/arm_motor_PID_real.yaml | 57 ++- .../config/encoder_parameters_mock.yaml | 24 +- .../config/encoder_parameters_real.yaml | 34 +- .../launch/jointstatepublisher.launch | 9 +- .../launch/testDifferential.launch | 3 + .../src/AbstractJoint.cpp | 39 -- .../src/AbstractJoint.hpp | 56 --- .../src/ArmControlActionServer.cpp | 356 +++++++++--------- src/wr_control_drive_arm/src/ArmMotor.cpp | 229 ----------- src/wr_control_drive_arm/src/ArmMotor.hpp | 259 ------------- .../src/DifferentialJoint.cpp | 129 ------- .../src/DifferentialJoint.hpp | 56 --- ...DifferentialJointToMotorSpeedConverter.cpp | 43 +++ ...DifferentialJointToMotorSpeedConverter.hpp | 31 ++ .../src/DirectJointToMotorSpeedConverter.cpp | 18 + .../src/DirectJointToMotorSpeedConverter.hpp | 28 ++ src/wr_control_drive_arm/src/Joint.cpp | 72 ++++ src/wr_control_drive_arm/src/Joint.hpp | 39 ++ .../src/JointStatePublisher.cpp | 84 +++-- src/wr_control_drive_arm/src/MathUtil.cpp | 8 + src/wr_control_drive_arm/src/MathUtil.hpp | 11 + src/wr_control_drive_arm/src/Motor.cpp | 45 +++ src/wr_control_drive_arm/src/Motor.hpp | 30 ++ .../src/RoboclawChannel.hpp | 6 + src/wr_control_drive_arm/src/SimpleJoint.cpp | 24 -- src/wr_control_drive_arm/src/SimpleJoint.hpp | 18 - .../src/SingleEncoderJointPositionMonitor.cpp | 46 +++ .../src/SingleEncoderJointPositionMonitor.hpp | 36 ++ .../src/testDifferential.cpp | 26 ++ .../launch/test/mock_arm.launch | 35 +- .../src/ArmTeleopLogic.cpp | 268 +++++++------ src/wroboarm_23/config/joint_limits.yaml | 18 +- testscrpt.py | 41 ++ 36 files changed, 1106 insertions(+), 1431 deletions(-) create mode 100644 src/wr_control_drive_arm/launch/testDifferential.launch delete mode 100644 src/wr_control_drive_arm/src/AbstractJoint.cpp delete mode 100644 src/wr_control_drive_arm/src/AbstractJoint.hpp delete mode 100644 src/wr_control_drive_arm/src/ArmMotor.cpp delete mode 100644 src/wr_control_drive_arm/src/ArmMotor.hpp delete mode 100644 src/wr_control_drive_arm/src/DifferentialJoint.cpp delete mode 100644 src/wr_control_drive_arm/src/DifferentialJoint.hpp create mode 100644 src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.cpp create mode 100644 src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.hpp create mode 100644 src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp create mode 100644 src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp create mode 100644 src/wr_control_drive_arm/src/Joint.cpp create mode 100644 src/wr_control_drive_arm/src/Joint.hpp create mode 100644 src/wr_control_drive_arm/src/MathUtil.cpp create mode 100644 src/wr_control_drive_arm/src/MathUtil.hpp create mode 100644 src/wr_control_drive_arm/src/Motor.cpp create mode 100644 src/wr_control_drive_arm/src/Motor.hpp create mode 100644 src/wr_control_drive_arm/src/RoboclawChannel.hpp delete mode 100644 src/wr_control_drive_arm/src/SimpleJoint.cpp delete mode 100644 src/wr_control_drive_arm/src/SimpleJoint.hpp create mode 100644 src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp create mode 100644 src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp create mode 100644 src/wr_control_drive_arm/src/testDifferential.cpp create mode 100755 testscrpt.py diff --git a/.clang-format b/.clang-format index c6ba5550..8d8dc719 100644 --- a/.clang-format +++ b/.clang-format @@ -4,4 +4,6 @@ AccessModifierOffset: -4 CommentPragmas: 'NOLINT' PackConstructorInitializers: CurrentLine AlignOperands: AlignAfterOperator -AlignTrailingComments: true \ No newline at end of file +AlignTrailingComments: true +ColumnLimit: 0 +SeparateDefinitionBlocks: Always \ No newline at end of file diff --git a/src/wr_control_drive_arm/CMakeLists.txt b/src/wr_control_drive_arm/CMakeLists.txt index 19ef7fde..a122dafe 100644 --- a/src/wr_control_drive_arm/CMakeLists.txt +++ b/src/wr_control_drive_arm/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.8) project(wr_control_drive_arm) -## Compile as C++11, supported in ROS Kinetic and newer -# add_compile_options(-std=c++11) +# # Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++17) -## Find catkin macros and libraries -## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) -## is used, also find other catkin packages +# # Find catkin macros and libraries +# # if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +# # is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp rospy @@ -15,201 +15,213 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs ) -## System dependencies are found with CMake's conventions +# # System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) - -## Uncomment this if the package has a setup.py. This macro ensures -## modules and global scripts declared therein get installed -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# # Uncomment this if the package has a setup.py. This macro ensures +# # modules and global scripts declared therein get installed +# # See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html # catkin_python_setup() -################################################ -## Declare ROS messages, services and actions ## -################################################ - -## To declare and build messages, services or actions from within this -## package, follow these steps: -## * Let MSG_DEP_SET be the set of packages whose message types you use in -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). -## * In the file package.xml: -## * add a build_depend tag for "message_generation" -## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in -## but can be declared for certainty nonetheless: -## * add a exec_depend tag for "message_runtime" -## * In this file (CMakeLists.txt): -## * add "message_generation" and every package in MSG_DEP_SET to -## find_package(catkin REQUIRED COMPONENTS ...) -## * add "message_runtime" and every package in MSG_DEP_SET to -## catkin_package(CATKIN_DEPENDS ...) -## * uncomment the add_*_files sections below as needed -## and list every .msg/.srv/.action file to be processed -## * uncomment the generate_messages entry below -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) - -## Generate messages in the 'msg' folder +# ############################################### +# # Declare ROS messages, services and actions ## +# ############################################### + +# # To declare and build messages, services or actions from within this +# # package, follow these steps: +# # * Let MSG_DEP_SET be the set of packages whose message types you use in +# # your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +# # * In the file package.xml: +# # * add a build_depend tag for "message_generation" +# # * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +# # * If MSG_DEP_SET isn't empty the following dependency has been pulled in +# # but can be declared for certainty nonetheless: +# # * add a exec_depend tag for "message_runtime" +# # * In this file (CMakeLists.txt): +# # * add "message_generation" and every package in MSG_DEP_SET to +# # find_package(catkin REQUIRED COMPONENTS ...) +# # * add "message_runtime" and every package in MSG_DEP_SET to +# # catkin_package(CATKIN_DEPENDS ...) +# # * uncomment the add_*_files sections below as needed +# # and list every .msg/.srv/.action file to be processed +# # * uncomment the generate_messages entry below +# # * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +# # Generate messages in the 'msg' folder # add_message_files( -# FILES -# Message1.msg -# Message2.msg +# FILES +# Message1.msg +# Message2.msg # ) -## Generate services in the 'srv' folder +# # Generate services in the 'srv' folder # add_service_files( -# FILES -# Service1.srv -# Service2.srv +# FILES +# Service1.srv +# Service2.srv # ) -## Generate actions in the 'action' folder +# # Generate actions in the 'action' folder # add_action_files( -# FILES -# Action1.action -# Action2.action +# FILES +# Action1.action +# Action2.action # ) -## Generate added messages and services with any dependencies listed here +# # Generate added messages and services with any dependencies listed here # generate_messages( -# DEPENDENCIES -# std_msgs # Or other packages containing msgs +# DEPENDENCIES +# std_msgs # Or other packages containing msgs # ) -################################################ -## Declare ROS dynamic reconfigure parameters ## -################################################ - -## To declare and build dynamic reconfigure parameters within this -## package, follow these steps: -## * In the file package.xml: -## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" -## * In this file (CMakeLists.txt): -## * add "dynamic_reconfigure" to -## find_package(catkin REQUIRED COMPONENTS ...) -## * uncomment the "generate_dynamic_reconfigure_options" section below -## and list every .cfg file to be processed - -## Generate dynamic reconfigure parameters in the 'cfg' folder +# ############################################### +# # Declare ROS dynamic reconfigure parameters ## +# ############################################### + +# # To declare and build dynamic reconfigure parameters within this +# # package, follow these steps: +# # * In the file package.xml: +# # * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +# # * In this file (CMakeLists.txt): +# # * add "dynamic_reconfigure" to +# # find_package(catkin REQUIRED COMPONENTS ...) +# # * uncomment the "generate_dynamic_reconfigure_options" section below +# # and list every .cfg file to be processed + +# # Generate dynamic reconfigure parameters in the 'cfg' folder # generate_dynamic_reconfigure_options( -# cfg/DynReconf1.cfg -# cfg/DynReconf2.cfg +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg # ) -################################### -## catkin specific configuration ## -################################### -## The catkin_package macro generates cmake config files for your package -## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if your package contains header files -## LIBRARIES: libraries you create in this project that dependent projects also need -## CATKIN_DEPENDS: catkin_packages dependent projects also need -## DEPENDS: system dependencies of this project that dependent projects also need +# ################################## +# # catkin specific configuration ## +# ################################## +# # The catkin_package macro generates cmake config files for your package +# # Declare things to be passed to dependent projects +# # INCLUDE_DIRS: uncomment this if your package contains header files +# # LIBRARIES: libraries you create in this project that dependent projects also need +# # CATKIN_DEPENDS: catkin_packages dependent projects also need +# # DEPENDS: system dependencies of this project that dependent projects also need catkin_package( -# INCLUDE_DIRS include -# LIBRARIES wr_control_drive_science -# CATKIN_DEPENDS roscpp rospy -# DEPENDS system_lib + + # INCLUDE_DIRS include + # LIBRARIES wr_control_drive_science + # CATKIN_DEPENDS roscpp rospy + # DEPENDS system_lib ) -########### -## Build ## -########### +# ########## +# # Build ## +# ########## -## Specify additional locations of header files -## Your package locations should be listed before other locations +# # Specify additional locations of header files +# # Your package locations should be listed before other locations include_directories( -# include + + # include ${catkin_INCLUDE_DIRS} ) -## Declare a C++ library - add_library( ${PROJECT_NAME} - src/ArmMotor.cpp - src/AbstractJoint.cpp - src/DifferentialJoint.cpp - src/SimpleJoint.cpp - ) - -## Add cmake target dependencies of the library -## as an example, code may need to be generated before libraries -## either from message generation or dynamic reconfigure +# # Declare a C++ library +add_library(${PROJECT_NAME} + src/DifferentialJointToMotorSpeedConverter.cpp + src/DirectJointToMotorSpeedConverter.cpp + src/Joint.cpp + src/MathUtil.cpp + src/Motor.cpp + src/SingleEncoderJointPositionMonitor.cpp +) + +# # Add cmake target dependencies of the library +# # as an example, code may need to be generated before libraries +# # either from message generation or dynamic reconfigure # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) -## Declare a C++ executable -## With catkin_make all packages are built within a single CMake context -## The recommended prefix ensures that target names across packages don't collide +# # Declare a C++ executable +# # With catkin_make all packages are built within a single CMake context +# # The recommended prefix ensures that target names across packages don't collide # add_executable(${PROJECT_NAME}_node src/wr_control_drive_arm_node.cpp) add_executable(ArmControlActionServer src/ArmControlActionServer.cpp) target_link_libraries(ArmControlActionServer ${catkin_LIBRARIES} ${PROJECT_NAME}) add_executable(JointStatePublisher src/JointStatePublisher.cpp) target_link_libraries(JointStatePublisher ${catkin_LIBRARIES} ${PROJECT_NAME}) - -## Rename C++ executable without prefix -## The above recommended prefix causes long target names, the following renames the -## target back to the shorter version for ease of user use -## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +add_executable(testDifferential src/testDifferential.cpp) +target_link_libraries(testDifferential ${catkin_LIBRARIES} ${PROJECT_NAME}) + +set_property(TARGET ArmControlActionServer PROPERTY CXX_STANDARD 17) +set_property(TARGET JointStatePublisher PROPERTY CXX_STANDARD 17) +set_property(TARGET ArmControlActionServer PROPERTY CXX_STANDARD_REQUIRED true) +set_property(TARGET JointStatePublisher PROPERTY CXX_STANDARD_REQUIRED true) +set_property(TARGET testDifferential PROPERTY CXX_STANDARD 17) +set_property(TARGET testDifferential PROPERTY CXX_STANDARD_REQUIRED true) + +# # Rename C++ executable without prefix +# # The above recommended prefix causes long target names, the following renames the +# # target back to the shorter version for ease of user use +# # e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") -## Add cmake target dependencies of the executable -## same as for the library above +# # Add cmake target dependencies of the executable +# # same as for the library above # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) -## Specify libraries to link a library or executable target against +# # Specify libraries to link a library or executable target against # target_link_libraries(${PROJECT_NAME}_node -# ${catkin_LIBRARIES} +# ${catkin_LIBRARIES} # ) -############# -## Install ## -############# +# ############ +# # Install ## +# ############ # all install targets should use catkin DESTINATION variables # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html -## Mark executable scripts (Python etc.) for installation -## in contrast to setup.py, you can choose the destination +# # Mark executable scripts (Python etc.) for installation +# # in contrast to setup.py, you can choose the destination # catkin_install_python(PROGRAMS -# scripts/my_python_script -# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) -## Mark executables for installation -## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# # Mark executables for installation +# # See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html # install(TARGETS ${PROJECT_NAME}_node -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) -## Mark libraries for installation -## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# # Mark libraries for installation +# # See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html # install(TARGETS ${PROJECT_NAME} -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} # ) -## Mark cpp header files for installation +# # Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ -# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} -# FILES_MATCHING PATTERN "*.h" -# PATTERN ".svn" EXCLUDE +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE # ) -## Mark other files for installation (e.g. launch and bag files, etc.) +# # Mark other files for installation (e.g. launch and bag files, etc.) # install(FILES -# # myfile1 -# # myfile2 -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} # ) -############# -## Testing ## -############# +# ############ +# # Testing ## +# ############ -## Add gtest based cpp test target and link libraries +# # Add gtest based cpp test target and link libraries # catkin_add_gtest(${PROJECT_NAME}-test test/test_wr_control_drive_science.cpp) # if(TARGET ${PROJECT_NAME}-test) -# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() -## Add folders to be run by python nosetests +# # Add folders to be run by python nosetests # catkin_add_nosetests(test) diff --git a/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml b/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml index 88d33a6e..e59fd363 100644 --- a/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml +++ b/src/wr_control_drive_arm/config/arm_motor_PID_mock.yaml @@ -1,64 +1,55 @@ rate: 50 controllers: - - setpointTopic: "/control/arm/00/setpoint" - feedbackTopic: "/control/arm/00/feedback" - outputTopic: "/control/arm/00/output" - P: 100 - I: 0 + - setpointTopic: "/control/arm/pid/turntable/setpoint" + feedbackTopic: "/control/arm/pid/turntable/feedback" + outputTopic: "/control/arm/pid/turntable/output" + P: 5 + I: 0.5 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/01/setpoint" - feedbackTopic: "/control/arm/01/feedback" - outputTopic: "/control/arm/01/output" - P: 100 - I: 0 + - setpointTopic: "/control/arm/pid/shoulder/setpoint" + feedbackTopic: "/control/arm/pid/shoulder/feedback" + outputTopic: "/control/arm/pid/shoulder/output" + P: 5 + I: 0.5 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/10/setpoint" - feedbackTopic: "/control/arm/10/feedback" - outputTopic: "/control/arm/10/output" - P: 100 - I: 0 + - setpointTopic: "/control/arm/pid/elbow/setpoint" + feedbackTopic: "/control/arm/pid/elbow/feedback" + outputTopic: "/control/arm/pid/elbow/output" + P: 5 + I: 0.5 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/11/setpoint" - feedbackTopic: "/control/arm/11/feedback" - outputTopic: "/control/arm/11/output" - P: 100 - I: 0 + - setpointTopic: "/control/arm/pid/forearmRoll/setpoint" + feedbackTopic: "/control/arm/pid/forearmRoll/feedback" + outputTopic: "/control/arm/pid/forearmRoll/output" + P: 5 + I: 0.5 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/20/setpoint" - feedbackTopic: "/control/arm/20/feedback" - outputTopic: "/control/arm/20/output" - P: 100 - I: 0 + - setpointTopic: "/control/arm/pid/wristPitch/setpoint" + feedbackTopic: "/control/arm/pid/wristPitch/feedback" + outputTopic: "/control/arm/pid/wristPitch/output" + P: 5 + I: 0.5 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/21/setpoint" - feedbackTopic: "/control/arm/21/feedback" - outputTopic: "/control/arm/21/output" - P: 100 - I: 0 - D: 0 - min: -1 - max: 1 - - - setpointTopic: "/control/arm/3000/setpoint" - feedbackTopic: "/control/arm/3000/feedback" - outputTopic: "/control/arm/3000/output" - P: 100 - I: 0 + - setpointTopic: "/control/arm/pid/wristRoll/setpoint" + feedbackTopic: "/control/arm/pid/wristRoll/feedback" + outputTopic: "/control/arm/pid/wristRoll/output" + P: 5 + I: 0.5 D: 0 min: -1 max: 1 diff --git a/src/wr_control_drive_arm/config/arm_motor_PID_real.yaml b/src/wr_control_drive_arm/config/arm_motor_PID_real.yaml index 108c62f4..a0da7801 100644 --- a/src/wr_control_drive_arm/config/arm_motor_PID_real.yaml +++ b/src/wr_control_drive_arm/config/arm_motor_PID_real.yaml @@ -1,63 +1,54 @@ rate: 50 controllers: - - setpointTopic: "/control/arm/00/setpoint" - feedbackTopic: "/control/arm/00/feedback" - outputTopic: "/control/arm/00/output" - P: 5 + - setpointTopic: "/control/arm/pid/turntable/setpoint" + feedbackTopic: "/control/arm/pid/turntable/feedback" + outputTopic: "/control/arm/pid/turntable/output" + P: 10 I: 0 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/01/setpoint" - feedbackTopic: "/control/arm/01/feedback" - outputTopic: "/control/arm/01/output" - P: 5 + - setpointTopic: "/control/arm/pid/shoulder/setpoint" + feedbackTopic: "/control/arm/pid/shoulder/feedback" + outputTopic: "/control/arm/pid/shoulder/output" + P: 10 I: 0 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/10/setpoint" - feedbackTopic: "/control/arm/10/feedback" - outputTopic: "/control/arm/10/output" - P: 5 + - setpointTopic: "/control/arm/pid/elbow/setpoint" + feedbackTopic: "/control/arm/pid/elbow/feedback" + outputTopic: "/control/arm/pid/elbow/output" + P: 10 I: 0 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/11/setpoint" - feedbackTopic: "/control/arm/11/feedback" - outputTopic: "/control/arm/11/output" - P: 5 + - setpointTopic: "/control/arm/pid/forearmRoll/setpoint" + feedbackTopic: "/control/arm/pid/forearmRoll/feedback" + outputTopic: "/control/arm/pid/forearmRoll/output" + P: 10 I: 0 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/20/setpoint" - feedbackTopic: "/control/arm/20/feedback" - outputTopic: "/control/arm/20/output" - P: 5 + - setpointTopic: "/control/arm/pid/wristPitch/setpoint" + feedbackTopic: "/control/arm/pid/wristPitch/feedback" + outputTopic: "/control/arm/pid/wristPitch/output" + P: 10 I: 0 D: 0 min: -1 max: 1 - - setpointTopic: "/control/arm/21/setpoint" - feedbackTopic: "/control/arm/21/feedback" - outputTopic: "/control/arm/21/output" - P: 5 - I: 0 - D: 0 - min: -1 - max: 1 - - - setpointTopic: "/control/arm/3000/setpoint" - feedbackTopic: "/control/arm/3000/feedback" - outputTopic: "/control/arm/3000/output" - P: 5 + - setpointTopic: "/control/arm/pid/wristRoll/setpoint" + feedbackTopic: "/control/arm/pid/wristRoll/feedback" + outputTopic: "/control/arm/pid/wristRoll/output" + P: 10 I: 0 D: 0 min: -1 diff --git a/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml b/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml index 5c855815..91e14a26 100644 --- a/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml +++ b/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml @@ -1,19 +1,19 @@ encoder_parameters: -# elbow - - counts_per_rotation: 1000 + elbow: + counts_per_rotation: 1000 offset: 500 -# forearm_roll - - counts_per_rotation: 1000 + forearmRoll: + counts_per_rotation: 1000 offset: 500 -# shoulder - - counts_per_rotation: 1000 + shoulder: + counts_per_rotation: 1000 offset: 500 -# turntable - - counts_per_rotation: 1000 + turntable: + counts_per_rotation: 1000 offset: 500 -# wrist_pitch - - counts_per_rotation: 1000 + wristPitch: + counts_per_rotation: 1000 offset: 500 -# wrist_roll - - counts_per_rotation: 1000 + wristRoll: + counts_per_rotation: 1000 offset: 500 diff --git a/src/wr_control_drive_arm/config/encoder_parameters_real.yaml b/src/wr_control_drive_arm/config/encoder_parameters_real.yaml index 1fce6c2e..b4d31f7c 100644 --- a/src/wr_control_drive_arm/config/encoder_parameters_real.yaml +++ b/src/wr_control_drive_arm/config/encoder_parameters_real.yaml @@ -1,19 +1,19 @@ encoder_parameters: -# elbow - - counts_per_rotation: -2048 - offset: 610 -# forearm_roll - - counts_per_rotation: -2048 - offset: 540 -# shoulder - - counts_per_rotation: -6144 - offset: 1129 -# turntable - - counts_per_rotation: 2048 - offset: 985 -# wrist_pitch - - counts_per_rotation: 2048 + elbow: + counts_per_rotation: 1850 + offset: 546 + forearmRoll: + counts_per_rotation: -1850 + offset: 576 + shoulder: + counts_per_rotation: 5550 + offset: 1281 + turntable: + counts_per_rotation: 6900 #7200 + offset: 90 + wristPitch: + counts_per_rotation: -1850 offset: 886 -# wrist_roll - - counts_per_rotation: 2048 - offset: 1050 + wristRoll: + counts_per_rotation: -1850 + offset: 981 diff --git a/src/wr_control_drive_arm/launch/jointstatepublisher.launch b/src/wr_control_drive_arm/launch/jointstatepublisher.launch index eb85aac1..8aa7f82c 100644 --- a/src/wr_control_drive_arm/launch/jointstatepublisher.launch +++ b/src/wr_control_drive_arm/launch/jointstatepublisher.launch @@ -1,9 +1,12 @@ - - - + + + \ No newline at end of file diff --git a/src/wr_control_drive_arm/launch/testDifferential.launch b/src/wr_control_drive_arm/launch/testDifferential.launch new file mode 100644 index 00000000..b6632b1a --- /dev/null +++ b/src/wr_control_drive_arm/launch/testDifferential.launch @@ -0,0 +1,3 @@ + + + \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/AbstractJoint.cpp b/src/wr_control_drive_arm/src/AbstractJoint.cpp deleted file mode 100644 index e88e5afa..00000000 --- a/src/wr_control_drive_arm/src/AbstractJoint.cpp +++ /dev/null @@ -1,39 +0,0 @@ -/** - * @file AbstractJoint.cpp - * @author Nichols Underwood - * @brief Implementation of the AbstractJoint class - * @date 2021-10-25 - */ - -#include "AbstractJoint.hpp" - -AbstractJoint::AbstractJoint(ros::NodeHandle &n, int numMotors){ - this->motors.resize(numMotors); -} - -auto AbstractJoint::getDegreesOfFreedom() const -> unsigned int{ - return this->motors.size(); -} - -auto AbstractJoint::getMotor(int motorIndex) const -> const std::unique_ptr&{ - return this->motors.at(motorIndex).motor; -} - -void AbstractJoint::configSetpoint(int degreeIndex, double position, double velocity){ - - this->motors.at(degreeIndex).position = position; - this->motors.at(degreeIndex).velocity = velocity; -} - - -void AbstractJoint::exectute(){ - for(auto &motorHandle : motors){ - motorHandle.motor->runToTarget(motorHandle.position, motorHandle.velocity); - } -} - -void AbstractJoint::stopJoint(){ - for(auto &motorHandle : motors){ - motorHandle.motor->setPower(0.F); - } -} \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/AbstractJoint.hpp b/src/wr_control_drive_arm/src/AbstractJoint.hpp deleted file mode 100644 index b395aa61..00000000 --- a/src/wr_control_drive_arm/src/AbstractJoint.hpp +++ /dev/null @@ -1,56 +0,0 @@ -/** - * @file AbstractJoint.hpp - * @author Nichols Underwood - * @brief Header file of the AbstractJoint class - * @date 2021-10-25 - */ - -#ifndef ABSTRACT_JOINT_GUARD -#define ABSTRACT_JOINT_GUARD - -#include "ArmMotor.hpp" -using std::vector; - -class AbstractJoint { -public: - struct MotorHandler{ - std::unique_ptr motor; - double position; - double velocity; - std::string jointTopicName; - std::string motorTopicName; - bool newVelocity; - }; - - AbstractJoint(ros::NodeHandle &n, int numMotors); - - // never used, need to be defined for compiler v-table - virtual auto getMotorPositions(const vector &jointPositions) -> vector = 0; - virtual auto getMotorVelocities(const vector &joinVelocities) -> vector = 0; - virtual auto getJointPositions(const vector &motorPositions) -> vector = 0; - - auto getDegreesOfFreedom() const -> unsigned int; - - auto getMotor(int motorIndex) const -> const std::unique_ptr&; - - void configSetpoint(int degreeIndex, double position, double velocity); - - void exectute(); - - void stopJoint(); - - virtual ~AbstractJoint() = default; - - AbstractJoint(const AbstractJoint&) = delete; - - auto operator=(const AbstractJoint&) -> AbstractJoint& = delete; - - AbstractJoint(AbstractJoint&&) = delete; - - auto operator=(AbstractJoint&&) -> AbstractJoint& = delete; - -protected: - vector motors; -}; - -#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 9b660b61..14892cd3 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -4,61 +4,63 @@ * @brief The exeutable file to run the Arm Control Action Server * @date 2022-12-05 */ +#include "DifferentialJointToMotorSpeedConverter.hpp" +#include "DirectJointToMotorSpeedConverter.hpp" +#include "Joint.hpp" +#include "Motor.hpp" +#include "RoboclawChannel.hpp" +#include "SingleEncoderJointPositionMonitor.hpp" #include "XmlRpcValue.h" +#include "ros/init.h" -#include "DifferentialJoint.hpp" -#include "SimpleJoint.hpp" -#include "ros/console.h" -#include "ros/ros.h" #include #include #include +#include #include #include #include +#include #include #include #include #include #include +#include +#include +#include using XmlRpc::XmlRpcValue; /** * @brief Refresh rate of ros::Rate */ -constexpr float CLOCK_RATE = 50; +constexpr float CLOCK_RATE{50}; -constexpr double IK_WARN_RATE = 1.0 / 2; +constexpr double IK_WARN_RATE{1.0 / 2}; -constexpr double JOINT_SAFETY_MAX_SPEED = 0.5; -constexpr double JOINT_SAFETY_HOLD_SPEED = 0.15; +constexpr double JOINT_SAFETY_MAX_SPEED{0.5}; +constexpr double JOINT_SAFETY_HOLD_SPEED{0.3}; /** * @brief Nessage cache size of publisher */ -constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; +constexpr std::uint32_t MESSAGE_CACHE_SIZE{10}; /** * @brief Period between timer callback */ -constexpr float TIMER_CALLBACK_DURATION = 1.0 / 50.0; +constexpr float TIMER_CALLBACK_DURATION{1.0 / 50.0}; /** * @brief Defines space for all Joint references */ -constexpr int NUM_JOINTS = 5; -std::array, NUM_JOINTS> joints; -// AbstractJoint *joints[numJoints]; -/** - * @brief The Joint State Publisher for MoveIt - */ -ros::Publisher jointStatePublisher; +std::unordered_map> namedJointMap; + /** * @brief Simplify the SimpleActionServer reference name */ -typedef actionlib::SimpleActionServer - Server; +using Server = actionlib::SimpleActionServer; /** * @brief The service server for enabling IK */ @@ -80,158 +82,92 @@ ros::ServiceClient enableServiceClient; * @param as The Action Server this is occuring on */ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, - Server *as) { + Server *server) { if (!IKEnabled) { - as->setAborted(); - ROS_WARN_THROTTLE( + server->setAborted(); + ROS_WARN_THROTTLE( // NOLINT(hicpp-no-array-decay,hicpp,hicpp-vararg,cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) IK_WARN_RATE, - "IK is disabled"); // NOLINT(hicpp-no-array-decay,hicpp,hicpp-vararg,cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) + "IK is disabled"); return; } - int currPoint = 1; - - std::cout << "start exec: " << goal->trajectory.points.size() << std::endl; - // For each point in the trajectory execution sequence... - for (const auto &name : goal->trajectory.joint_names) { - std::cout << name << "\t"; + for (const auto &jointName : goal->trajectory.joint_names) { + std::cout << jointName << "\t"; } std::cout << std::endl; - for (const auto &currTargetPosition : goal->trajectory.points) { - for (double pos : currTargetPosition.positions) { - std::cout << std::round(pos * 100) / 100 << "\t"; + for (const auto &waypoint : goal->trajectory.points) { + for (const auto &jointVal : waypoint.positions) { + std::cout << jointVal << "\t"; } std::cout << std::endl; } + for (const auto &currTargetPosition : goal->trajectory.points) { - // Track whether or not the current position is done - bool hasPositionFinished = false; - // Keep max loop rate at 50 Hz - ros::Rate loop{CLOCK_RATE}; + + if (!IKEnabled) { + server->setAborted(); + std::cout << "Over current fault!" << std::endl; + return; + } const double VELOCITY_MAX = abs(*std::max_element( currTargetPosition.velocities.begin(), currTargetPosition.velocities.end(), - [](double a, double b) -> bool { return abs(a) < abs(b); })); - - ArmMotor *currmotor = NULL; - int currItr = 0; - // std::cout << currPoint << " / " << goal->trajectory.points.size() << - // std::endl; - currPoint++; - for (const auto &joint : joints) { - for (int i = 0; i < joint->getDegreesOfFreedom(); i++) { - double velocity = - VELOCITY_MAX == 0.F - ? JOINT_SAFETY_HOLD_SPEED - : JOINT_SAFETY_MAX_SPEED * currTargetPosition.velocities[currItr] / VELOCITY_MAX; - std::cout << "config setpoint: " << - currTargetPosition.positions[currItr] << ":" << velocity << - std::endl; - joint->configSetpoint(i, currTargetPosition.positions[currItr], - velocity); - currItr++; - } - joint->exectute(); + [](double lhs, double rhs) -> bool { return abs(lhs) < abs(rhs); })); + + for (uint32_t i = 0; i < goal->trajectory.joint_names.size(); ++i) { + auto jointVelocity{JOINT_SAFETY_HOLD_SPEED}; + if (VELOCITY_MAX != 0) + jointVelocity = currTargetPosition.velocities.at(i) / VELOCITY_MAX * JOINT_SAFETY_MAX_SPEED; + + namedJointMap.at(goal->trajectory.joint_names.at(i))->setTarget(currTargetPosition.positions.at(i), jointVelocity); } + } - // While the current position is not complete yet... - while (!hasPositionFinished && ros::ok()) { - // Assume the current action is done until proven otherwise - hasPositionFinished = true; - // Create the Joint State message for the current update cycle - - // For each joint specified in the currTargetPosition... - for (const auto &joint : joints) { - - for (int k = 0; k < joint->getDegreesOfFreedom(); k++) { - // if (joint->getMotor(k)->getMotorState() == - // MotorState::MOVING) { - // std::cout << "Moving" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == - // MotorState::RUN_TO_TARGET) { - // std::cout << "Run to target" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == - // MotorState::STALLING) { - // std::cout << "Stalling" << std::endl; - // } else if (joint->getMotor(k)->getMotorState() == - // MotorState::STOP) { - // std::cout << "Stop" << std::endl; - // } else { - // std::cout << "Error" << std::endl; - // } - - if (joint->getMotor(k)->getMotorState() == - MotorState::STALLING) { - std::cout << "ACS stall detected" << std::endl; - IKEnabled = false; - std_srvs::Trigger srv; - if (enableServiceClient.call(srv)) { - ROS_WARN( - "%s", - (std::string{"PLACEHOLDER_NAME: "} + - srv.response.message) - .data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - } else { - ROS_WARN( - "Error: failed to call service " - "PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - } - } else { - hasPositionFinished &= - joint->getMotor(k)->getMotorState() == - MotorState::STOP; - std::cout << joint->getMotor(k)->getMotorName() << " state: " << (joint->getMotor(k)->getMotorState() == MotorState::STOP) << std::endl; - } - // DEBUGGING OUTPUT: Print each motor's name, radian - // position, encoder position, and power - // std::cout << std::setw(30) << joint->getMotor(k)->getRads() - // << std::endl; - } - - joint->exectute(); - - // if (!joint->exectute()) { - // IKEnabled = false; - // std_srvs::Trigger srv; - // if (enableServiceClient.call(srv)) { - // ROS_WARN("%s", (std::string{"PLACEHOLDER_NAME: "} + srv.response.message).data()); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - // } else { - // ROS_WARN("Error: failed to call service PLACEHOLDER_NAME"); // NOLINT(cppcoreguidelines-pro-bounds-array-to-pointer-decay, cppcoreguidelines-pro-type-vararg) - // } - // return; - // } - } - // Sleep until the next update cycle - loop.sleep(); + auto waypointComplete{false}; + ros::Rate updateRate{CLOCK_RATE}; + + while (!waypointComplete && ros::ok() && !server->isNewGoalAvailable()) { + + if (!IKEnabled) { + server->setAborted(); + std::cout << "Over current fault!" << std::endl; + return; + } + + waypointComplete = true; + for (const auto &[_, joint] : namedJointMap) { + waypointComplete &= joint->hasReachedTarget(); } + updateRate.sleep(); } + // Report preemption if it occurred + if (server->isNewGoalAvailable()) + server->setPreempted(); // When all positions have been reached, set the current task as succeeded + else + server->setSucceeded(); + std::cout << "Action Complete!" << std::endl; +} - as->setSucceeded(); +auto getEncoderConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> EncoderConfiguration { + return {.countsPerRotation = static_cast(params[jointName]["counts_per_rotation"]), + .offset = static_cast(params[jointName]["offset"])}; } -/** - * @brief publishes the arm's position - */ -void publishJointStates(const ros::TimerEvent &event) { - std::vector names; - std::vector positions; - sensor_msgs::JointState js_msg; - - for (const auto &joint : joints) { - for (int i = 0; i < joint->getDegreesOfFreedom(); i++) { - names.push_back(joint->getMotor(i)->getMotorName()); - positions.push_back(joint->getMotor(i)->getRads()); +void checkOverCurrentFaults(const std::vector> &motors){ + for(const auto& motor : motors){ + if (motor->isOverCurrent()) { + IKEnabled = false; + std::cout << "Over current fault!" << std::endl; + + for (const auto& joint : namedJointMap) { + joint.second->stop(); + } } + // TODO: arbitrate control to old arm driver } - - js_msg.name = names; - js_msg.position = positions; - js_msg.header.stamp = ros::Time::now(); - // Publish the Joint State message - jointStatePublisher.publish(js_msg); } /** @@ -255,47 +191,105 @@ auto main(int argc, char **argv) -> int { // Initialize all motors with their MoveIt name, WRoboclaw initialization, // and reference to the current node - auto elbowPitch_joint = std::make_unique( - "elbowPitch_joint", 1, 0, - static_cast(encParams[0]["counts_per_rotation"]), - static_cast(encParams[0]["offset"]), n); - auto elbowRoll_joint = std::make_unique( - "elbowRoll_joint", 1, 1, - static_cast(encParams[1]["counts_per_rotation"]), - static_cast(encParams[1]["offset"]), n); - auto shoulder_joint = std::make_unique( - "shoulder_joint", 0, 1, - static_cast(encParams[2]["counts_per_rotation"]), - static_cast(encParams[2]["offset"]), n); - auto turntable_joint = std::make_unique( - "turntable_joint", 0, 0, - static_cast(encParams[3]["counts_per_rotation"]), - static_cast(encParams[3]["offset"]), n); - auto wristPitch_joint = std::make_unique( - "wristPitch_joint", 2, 0, - static_cast(encParams[4]["counts_per_rotation"]), - static_cast(encParams[4]["offset"]), n); - auto wristRoll_link = std::make_unique( - "wristRoll_link", 2, 1, - static_cast(encParams[5]["counts_per_rotation"]), - static_cast(encParams[5]["offset"]), n); std::cout << "init motors" << std::endl; + /** + * @brief The list of motors + */ + std::vector> motors{}; + + using std::literals::string_literals::operator""s; + + const auto turntableMotor{std::make_shared("aux0"s, RoboclawChannel::A, n)}; + const auto shoulderMotor{std::make_shared("aux0"s, RoboclawChannel::B, n)}; + const auto elbowMotor{std::make_shared("aux1"s, RoboclawChannel::A, n)}; + const auto forearmRollMotor{std::make_shared("aux1"s, RoboclawChannel::B, n)}; + const auto wristLeftMotor{std::make_shared("aux2"s, RoboclawChannel::A, n)}; + const auto wristRightMotor{std::make_shared("aux2"s, RoboclawChannel::B, n)}; + + motors.push_back(turntableMotor); + motors.push_back(shoulderMotor); + motors.push_back(elbowMotor); + motors.push_back(forearmRollMotor); + motors.push_back(wristLeftMotor); + motors.push_back(wristRightMotor); + + const auto turntablePositionMonitor{std::make_shared( + "aux0"s, + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "turntable"), + n)}; + const auto shoulderPositionMonitor{std::make_shared( + "aux0"s, + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "shoulder"), + n)}; + const auto elbowPositionMonitor{std::make_shared( + "aux1"s, + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "elbow"), + n)}; + const auto forearmRollPositionMonitor{std::make_shared( + "aux1"s, + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "forearmRoll"), + n)}; + const auto wristPitchPositionMonitor{std::make_shared( + "aux2"s, + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "wristPitch"), + n)}; + const auto wristRollPositionMonitor{std::make_shared( + "aux2"s, + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "wristRoll"), + n)}; + + const auto turntableSpeedConverter{std::make_shared(turntableMotor, MotorSpeedDirection::REVERSE)}; + const auto shoulderSpeedConverter{std::make_shared(shoulderMotor, MotorSpeedDirection::REVERSE)}; + const auto elbowSpeedConverter{std::make_shared(elbowMotor, MotorSpeedDirection::REVERSE)}; + const auto forearmRollSpeedConverter{std::make_shared(forearmRollMotor, MotorSpeedDirection::REVERSE)}; + const auto differentialSpeedConverter{std::make_shared(wristLeftMotor, wristRightMotor)}; + // Initialize all Joints - joints.at(0) = - std::make_unique(std::move(elbowPitch_joint), n); - joints.at(1) = std::make_unique(std::move(elbowRoll_joint), n); - joints.at(2) = std::make_unique(std::move(shoulder_joint), n); - joints.at(3) = std::make_unique(std::move(turntable_joint), n); - joints.at(4) = std::make_unique( - std::move(wristPitch_joint), std::move(wristRoll_link), n, - "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", - "/control/arm/21/"); + std::cout << "init joints" << std::endl; + namedJointMap.insert({"turntable_joint", std::make_unique( + "turntable"s, + [turntablePositionMonitor]() -> double { return (*turntablePositionMonitor)(); }, + [turntableSpeedConverter](double speed) { (*turntableSpeedConverter)(speed); }, + n)}); + namedJointMap.insert({"shoulder_joint", std::make_unique( + "shoulder", + [shoulderPositionMonitor]() -> double { return (*shoulderPositionMonitor)(); }, + [shoulderSpeedConverter](double speed) { (*shoulderSpeedConverter)(speed); }, + n)}); + namedJointMap.insert({"elbowPitch_joint", std::make_unique( + "elbow", + [elbowPositionMonitor]() -> double { return (*elbowPositionMonitor)(); }, + [elbowSpeedConverter](double speed) { (*elbowSpeedConverter)(speed); }, + n)}); + namedJointMap.insert({"elbowRoll_joint", std::make_unique( + "forearmRoll", + [forearmRollPositionMonitor]() -> double { return (*forearmRollPositionMonitor)(); }, + [forearmRollSpeedConverter](double speed) { (*forearmRollSpeedConverter)(speed); }, + n)}); + namedJointMap.insert({"wristPitch_joint", std::make_unique( + "wristPitch", + [wristPitchPositionMonitor]() -> double { return (*wristPitchPositionMonitor)(); }, + [converter = differentialSpeedConverter](double speed) { converter->setPitchSpeed(speed); }, + n)}); + namedJointMap.insert({"wristRoll_link", std::make_unique( + "wristRoll", + [wristRollPositionMonitor]() -> double { return (*wristRollPositionMonitor)(); }, + [converter = differentialSpeedConverter](double speed) { converter->setRollSpeed(speed); }, + n)}); + // Initialize the Action Server - Server server(n, "/arm_controller/follow_joint_trajectory", - boost::bind(&execute, _1, &server), false); + Server server( + n, "/arm_controller/follow_joint_trajectory", + [&server](auto goal) { execute(goal, &server); }, false); // Start the Action Server server.start(); std::cout << "server started" << std::endl; @@ -315,6 +309,8 @@ auto main(int argc, char **argv) -> int { enableServiceClient = n.serviceClient("PLACEHOLDER_NAME"); + ros::Timer currentTimer = n.createTimer(ros::Duration{TIMER_CALLBACK_DURATION}, [&motors](const ros::TimerEvent& event) { checkOverCurrentFaults(motors); }); + std::cout << "entering ROS spin..." << std::endl; // ROS spin for communication with other nodes ros::spin(); diff --git a/src/wr_control_drive_arm/src/ArmMotor.cpp b/src/wr_control_drive_arm/src/ArmMotor.cpp deleted file mode 100644 index 10f25e05..00000000 --- a/src/wr_control_drive_arm/src/ArmMotor.cpp +++ /dev/null @@ -1,229 +0,0 @@ -/** - * @file ArmMotor.cpp - * @author Ben Nowotny - * @brief The implementation of the ArmMotor class - * @date 2021-04-05 - */ -#include "ArmMotor.hpp" -#include -#include -#include -#include - -/// Allow for referencing the UInt32 message type easier -using Std_UInt32 = std_msgs::UInt32::ConstPtr; -using Std_Float64 = std_msgs::Float64::ConstPtr; -using Std_Bool = std_msgs::Bool::ConstPtr; - -auto ArmMotor::corrMod(double i, double j) -> double { - // Stem i%j by j, which in modular arithmetic is the same as adding 0. - return std::fmod(std::fmod(std::abs(j) * i / j, std::abs(j)) + j, std::abs(j)); -} - -/// Currently consistent with the rad->enc equation as specified here. -auto ArmMotor::radToEnc(double rads) const -> uint32_t { - double remappedEnc = ArmMotor::corrMod(rads, 2 * M_PI) / (2 * M_PI); - return ArmMotor::corrMod((this->COUNTS_PER_ROTATION * remappedEnc) + this->ENCODER_OFFSET, abs(this->COUNTS_PER_ROTATION)); -} - -auto ArmMotor::encToRad(uint32_t enc) const -> double { - double remappedEnc = ArmMotor::corrMod(static_cast(enc - this->ENCODER_OFFSET), abs(static_cast(this->COUNTS_PER_ROTATION))) / this->COUNTS_PER_ROTATION; - return ArmMotor::corrMod(remappedEnc * 2 * M_PI + M_PI, 2 * M_PI) - M_PI; -} - -/// Currently consistent with the enc->rad equation as specified here. -auto ArmMotor::getRads() const -> double { - return ArmMotor::encToRad(this->getEncoderCounts()); -} - -void ArmMotor::storeEncoderVals(const Std_UInt32 &msg) { - // Store the message value in this ArmMotor's encoderVal variable - this->encoderVal = msg->data; - - // Send feedback - std_msgs::Float64 feedbackMsg; - feedbackMsg.data = ArmMotor::encToRad(msg->data); - if (!readOnly) - this->feedbackPub.publish(feedbackMsg); - - if (this->currState == MotorState::RUN_TO_TARGET) { - // std::cout << "[2] motor " << motorName << " position " << (hasReachedTarget(this->target) ? "at target " : "not at target ") << this->target << ":" << this->encoderVal << std::endl; - if (hasReachedTarget(this->target)) { - // std::cout << "[1] stop motor" << std::endl; - this->setPower(0.F, MotorState::STOP); - } - } -} - -void ArmMotor::redirectPowerOutput(const Std_Float64 &msg) { - // Set the speed to be the contained data - if (abs(msg->data) > 1) - std::cout << "Received power " << msg->data << " from PID for motor " << motorName << std::endl; - if (this->getMotorState() == MotorState::RUN_TO_TARGET) - this->setPower(static_cast(msg->data) * this->maxPower, MotorState::RUN_TO_TARGET); -} - -void ArmMotor::storeStallStatus(const Std_Bool &msg) { - if (static_cast(msg->data)) { - if ((ros::Time::now() - beginStallTime).toSec() >= STALL_THRESHOLD_TIME) { - std::cout << "over lim" << std::endl; - this->setPower(0.0F, MotorState::STALLING); - } - } else { - beginStallTime = ros::Time::now(); - } -} - -/// controllerID is constrained between [0,3] -/// motorID is constrained between [0,1] -ArmMotor::ArmMotor( - std::string motor_name, - unsigned int controllerID, - unsigned int motorID, - int64_t countsPerRotation, - int64_t offset, - ros::NodeHandle &n, - bool readOnly) : COUNTS_PER_ROTATION{countsPerRotation}, - ENCODER_BOUNDS{0, std::abs(countsPerRotation)}, - ENCODER_OFFSET{offset}, - motorName{std::move(motor_name)}, - controllerID{controllerID}, - motorID{motorID}, - currState{MotorState::STOP}, - power{0.F}, - maxPower{0.F}, - encoderVal{static_cast(offset)}, - readOnly{readOnly} { - - // Check validity of WRoboclaw and motor IDs - if (controllerID > 3) - throw std::invalid_argument{std::string{"Controller ID "} + std::to_string(controllerID) + "is only valid on [0,3]"}; - if (motorID > 1) - throw std::invalid_argument{std::string{"Motor ID "} + std::to_string(motorID) + " is only valid on [0,1]"}; - - // Create the topic string prefix for WRoboclaw controllers - std::string tpString = std::string{"/hsi/roboclaw/aux"} + std::to_string(controllerID); - std::string controlString = "/control/arm/" + std::to_string(controllerID) + std::to_string(motorID); - - // Create the appropriate encoder-reading and speed-publishing subscribers and advertisers, respectfully - this->encRead = n.subscribe(tpString + "/enc/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE, &ArmMotor::storeEncoderVals, this); - if (!readOnly) { - this->speedPub = n.advertise(tpString + "/cmd/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE); - this->targetPub = n.advertise(controlString + "/setpoint", ArmMotor::MESSAGE_CACHE_SIZE); - this->feedbackPub = n.advertise(controlString + "/feedback", ArmMotor::MESSAGE_CACHE_SIZE); - } - this->outputRead = n.subscribe(controlString + "/output", ArmMotor::MESSAGE_CACHE_SIZE, &ArmMotor::redirectPowerOutput, this); - this->stallRead = n.subscribe(tpString + "/curr/over_lim/" + (motorID == 0 ? "left" : "right"), ArmMotor::MESSAGE_CACHE_SIZE, &ArmMotor::storeStallStatus, this); - - std::cout << this->motorName << ": " << this->COUNTS_PER_ROTATION << std::endl; -} - -auto ArmMotor::getEncoderCounts() const -> uint32_t { - return this->encoderVal; -} - -void ArmMotor::runToTarget(uint32_t targetCounts, float power) { - // std::cout << "run to enc: " << targetCounts << std::endl; - this->runToTarget(targetCounts, power, false); -} - -auto ArmMotor::hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const -> bool { - // std::cout << "TOLERANCE: " << tolerance << std::endl; - // Compute the upper and lower bounds in the finite encoder space - int32_t lBound = ArmMotor::corrMod(static_cast(targetCounts - tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); - int32_t uBound = ArmMotor::corrMod(static_cast(targetCounts + tolerance), static_cast(ArmMotor::ENCODER_BOUNDS[1])); - // std::cout << "LBOUND: " << (lBound) << " UBOUND: " << (uBound) << std::endl; - auto position = ArmMotor::corrMod(getEncoderCounts(), ENCODER_BOUNDS[1]); - // std::cout << "POSITION RAW: " << encToRad(getEncoderCounts()) << "/" << getEncoderCounts() << std::endl; - // std::cout << "POSITION: " << encToRad(position) << "/" << position << std::endl; - // If the computed lower bound is lower than the upper bound, perform the computation normally - if (lBound < uBound) - return position <= uBound && position >= lBound; - // Otherwise, check if the value is outside either bound and negate the response - return position <= uBound || position >= lBound; -} - -/// Current tolerance is ±0.1 degree w.r.t. the current number of counts per rotation -auto ArmMotor::hasReachedTarget(uint32_t targetCounts) const -> bool { - auto tol = ArmMotor::TOLERANCE_RATIO * static_cast(std::abs(this->COUNTS_PER_ROTATION)); - return ArmMotor::hasReachedTarget(targetCounts, std::max(10.0, tol)); -} - -auto ArmMotor::getMotorState() const -> MotorState { - return this->currState; -} - -void ArmMotor::setPower(float power) { - this->setPower(power, power == 0.F ? MotorState::STOP : MotorState::MOVING); -} - -/// This method auto-publishes the speed command to the WRoboclaws -void ArmMotor::setPower(float power, MotorState state) { - // Check the bounds of the parameter - if (abs(power) > 1) - throw std::invalid_argument{std::string{"Power "} + std::to_string(power) + " is not on the interval [-1, 1]"}; - - if (!readOnly) { - // Set up and send the speed message - this->power = power; - this->powerMsg.data = power * INT16_MAX; - this->speedPub.publish(this->powerMsg); - // Update the cur.nt motor state based on the power command input - this->currState = state; - } -} - -void ArmMotor::runToTarget(uint32_t targetCounts, float power, bool block) { - this->target = targetCounts; - this->maxPower = abs(power); - - std_msgs::Float64 setpointMsg; - setpointMsg.data = ArmMotor::encToRad(targetCounts); - if (!readOnly) - this->targetPub.publish(setpointMsg); - - // If we are not at our target... - if (!this->hasReachedTarget(targetCounts)) { - // std::cout << "has not reached target" << std::endl; - // Set the power in the correct direction and continue running to the target - this->currState = MotorState::RUN_TO_TARGET; - - // long int direction = targetCounts - this->getEncoderCounts(); - // power = abs(power) * (corrMod(direction, ((long int)this->COUNTS_PER_ROTATION)) < corrMod(-direction, ((long int)this->COUNTS_PER_ROTATION)) ? 1 : -1); - // this->setPower(power, MotorState::RUN_TO_TARGET); - - // Otherwise, stop the motor - } else { - // std::cout << "has reached target" << std::endl; - this->setPower(0.F, MotorState::STOP); - } - // If this is a blocking call... - if (block) { - // Wait until the motor has reached the target, then stop - while (!this->hasReachedTarget(targetCounts)) - ; - this->setPower(0.F, MotorState::RUN_TO_TARGET); - } -} - -void ArmMotor::runToTarget(double rads, float power) { - // std::cout << "run to target: " << rads << ":" << this->radToEnc(rads) << ":" << this->getEncoderCounts() << std::endl; - - runToTarget(this->radToEnc(rads), power, false); -} - -auto ArmMotor::getMotorName() const -> std::string { - return this->motorName; -} - -auto ArmMotor::getMotorID() const -> unsigned int { - return this->motorID; -} - -auto ArmMotor::getControllerID() const -> unsigned int { - return this->controllerID; -} - -auto ArmMotor::getPower() const -> float { - return this->power; -} \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/ArmMotor.hpp b/src/wr_control_drive_arm/src/ArmMotor.hpp deleted file mode 100644 index 9ad871c2..00000000 --- a/src/wr_control_drive_arm/src/ArmMotor.hpp +++ /dev/null @@ -1,259 +0,0 @@ -/** - * @file ArmMotor.hpp - * @author Ben Nowotny - * @brief Header file of the ArmMotor class - * @date 2021-04-05 - */ - -#include "ros/ros.h" -#include "std_msgs/Bool.h" -#include "std_msgs/Float64.h" -#include "std_msgs/Int16.h" -#include "std_msgs/UInt32.h" -#include -#include -#include - -/** - * @brief An enumeration of states for a motor to be in. - */ -enum class MotorState { - /// A Motor is stopped (not moving, 0 power command) - STOP, - /// A Motor is moving (non-0 power command) - MOVING, - /// A Motor is running to a given target - RUN_TO_TARGET, - /// A Motor is stalling (over safety current limit) - STALLING -}; - -/** - * @brief A way to control arm motors with WRoboclaw - */ -class ArmMotor { -private: - /// Time tolerance of over-current detection before a stall fault is - /// triggered - static constexpr float STALL_THRESHOLD_TIME = 0.5; - /// Tolerance ratio w.r.t the counts per rotation for encoder - /// run-to-position motion - static constexpr double TOLERANCE_RATIO = 0.1 / 360; - /// Size of ROS Topic message caches - static constexpr uint32_t MESSAGE_CACHE_SIZE = 10; - /// The number of encoder counts per rotation - int64_t const COUNTS_PER_ROTATION; - /// The upper and lower bounds of encoder rotation for absolute encoders - /// (index 0 is lower, index 1 is upper) - std::array const ENCODER_BOUNDS; - /// zero position of motor - int64_t const ENCODER_OFFSET; - /// The current state of the motor - std::atomic currState; - /// The joint name of the current motor - std::string motorName; - /// The ID of the WRoboclaw controller - unsigned int controllerID; - /// The ID of the motor within the WRoboclaw controller - unsigned int motorID; - /// The current encoder value - uint32_t encoderVal; - /// Target encoder counts for run to target - uint32_t target; - /// The ROS Subscriber that reads the encoders - ros::Subscriber encRead; - /// The ROS Publisher that sets the encoder targets - ros::Publisher targetPub; - /// The ROS Publisher that sets encoder feedback data - ros::Publisher feedbackPub; - /// The ROS Subscriber that reads controlled output data - ros::Subscriber outputRead; - /// The ROS Publisher that publishes motor speed commands - ros::Publisher speedPub; - /// The most recent power message sent - std_msgs::Int16 powerMsg; - /// The ROS Subscriber that reads stall status data - ros::Subscriber stallRead; - /// The time when the motor began stalling - ros::Time beginStallTime; - /// Motor power - float power; - /// Maximum absolute motor power in RUN_TO_POSITION mode. - std::atomic maxPower; - /// Whether or not this motor is read-only - bool readOnly; - - /** - * @brief A static conversion from radians to encoder counts - * - * @param rad The input number of radians - * @return uint32_t The corresponding encoder count bounded by - * ENCODER_BOUNDS - */ - auto radToEnc(double rad) const -> uint32_t; - - /** - * @brief A static conversion from encoder counts to radians - * - * @param enc The input number of encoder counts - * @return double The corresponding radian measure - */ - auto encToRad(uint32_t enc) const -> double; - - /** - * @brief Subscriber callback for encRead, captures the encoder value of the - * current motor - * - * @param msg The encoder value message as captured by encRead - */ - void storeEncoderVals(const std_msgs::UInt32::ConstPtr &msg); - - /** - * @brief Subscriber callback for outputRead, captures the PID output and - * sets the speed directly - * - * @param msg The PID output as captured by outputRead - */ - void redirectPowerOutput(const std_msgs::Float64::ConstPtr &msg); - - /** - * @brief Subscriber callback for stallRead, captures the stall status of - * the current motor - * - * @param msg The stall status of the current motor - */ - void storeStallStatus(const std_msgs::Bool::ConstPtr &msg); - - void setPower(float power, MotorState state); - - /** - * @brief Performs Euclidean correct modulus between two inputs of the same - * type - * - * @param i The dividend of the modulus - * @param j The divisor of the modulus - * @return double The Euclidean-correct remainder bounded on [0, j) - */ - static auto corrMod(double i, double j) -> double; - -public: - /** - * @brief Constructs a new ArmMotor - * - * @param motorName The joint name of the motor - * @param controllerID The WRoboclaw controller ID for this motor - * @param motorID The motor ID within its WRoboclaw controller - * @param n A NodeHandle reference to the constructing Node - * @param readOnly whether this motor will inhibit control messages - */ - ArmMotor(std::string motorName, unsigned int controllerID, - unsigned int motorID, int64_t countsPerRotation, int64_t offset, - ros::NodeHandle &n, bool readOnly = false); - - /** - * @brief Gets the encoder value of the motor - * - * @return uint32_t The current encoder value of the motor - */ - auto getEncoderCounts() const -> uint32_t; - - /** - * @brief Sends the motor to run to a target encoder value at a given power - * without blocking - * - * @param targetCounts The target encoder value for the motor - * @param power The power to move the motor at (Bounded between [-1, 1]) - */ - void runToTarget(uint32_t targetCounts, float power); - - /** - * @brief Sends the motor to run to a target encoder value at a given power - * - * @param targetCounts The target encoder value for the motor - * @param power The power to move the motor at (Bounded between [-1, 1]) - * @param block Specifies whether or not this action should block until it - * is complete - * @return True if the motor had stalled, and false otherwise - */ - void runToTarget(uint32_t targetCounts, float power, bool block); - - /** - * @brief Sends the motor to run to a specified position at a given power - * - * @param rads The position to send the motor to (specified in radians) - * @param power The power to move the motor at (Bounded between [-1, 1]) - * @return True if the motor had stalled, and false otherwise - */ - void runToTarget(double rads, float power); - - /** - * @brief Get the current state of the ArmMotor - * - * @return MotorState The current state of the ArmMotor - */ - auto getMotorState() const -> MotorState; - - /** - * @brief Set the motor power - * - * @param power The power to set the motor at (Bounded between [-1, 1]) - */ - void setPower(float power); - - /** - * @brief Get the radian measure of the current motor - * - * @return double The radian measure of the current motor's position - */ - auto getRads() const -> double; - - /** - * @brief Get the name of the ArmMotor - * - * @return std::string The name of the ArmMotor - */ - auto getMotorName() const -> std::string; - - /** - * @brief Get the name of the ArmMotor - * - * @return std::string The controller ID of the ArmMotor - */ - auto getControllerID() const -> unsigned int; - - /** - * @brief Get the name of the ArmMotor - * - * @return std::string The motor ID of the ArmMotor - */ - auto getMotorID() const -> unsigned int; - - /** - * @brief Checks if the motor is currently within a pre-specified tolerance - * of a target - * - * @param targetCounts The target to test against - * @return true The motor was within the target tolerance - * @return false The motor was outside of the target tolerance - */ - auto hasReachedTarget(uint32_t targetCounts) const -> bool; - - /** - * @brief Checks if the motor is currently within a given tolerance of a - * target - * - * @param targetCounts The target to test against - * @param tolerance The tolerance to give when testing the target - * @return true The motor was within the target tolerance - * @return false The motor was outside the target tolerance - */ - auto hasReachedTarget(uint32_t targetCounts, uint32_t tolerance) const - -> bool; - - /** - * @brief Get the most recently set motor power - * - * @return float Last motor power setting - */ - auto getPower() const -> float; -}; diff --git a/src/wr_control_drive_arm/src/DifferentialJoint.cpp b/src/wr_control_drive_arm/src/DifferentialJoint.cpp deleted file mode 100644 index 809a5772..00000000 --- a/src/wr_control_drive_arm/src/DifferentialJoint.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/** - * @file DifferentialJoint.cpp - * @author Nicholas Underwood - * @brief Header file of the DifferentialJoint class - * @date 2021-10-25 - */ - -#include "DifferentialJoint.hpp" -#include -using std::vector; - -constexpr std::array, 2> DifferentialJoint::MOTOR_TO_JOINT_MATRIX; -constexpr std::array, 2> DifferentialJoint::JOINT_TO_MOTOR_MATRIX; - -DifferentialJoint::DifferentialJoint(std::unique_ptr leftMotor, std::unique_ptr rightMotor, ros::NodeHandle &n, - const std::string &pitchTopicName, const std::string &rollTopicName, - const std::string &leftTopicName, const std::string &rightTopicName) - : AbstractJoint(n, DEGREES_OF_FREEDOM) { - this->motors.at(0) = {std::move(leftMotor), 0, 0, "", "", false}; - this->motors.at(1) = {std::move(rightMotor), 0, 0, "", "", false}; - - // TODO: This should NOT be bypassing the motors in handling PID. This should do frame conversions and pass the results into the motors to handle the actual ROS comms - this->pitchOutputSubscriber = n.subscribe(pitchTopicName + "/output", MESSAGE_CACHE_SIZE, &DifferentialJoint::handoffPitchOutput, this); - this->rollOutputSubscriber = n.subscribe(rollTopicName + "/output", MESSAGE_CACHE_SIZE, &DifferentialJoint::handoffRollOutput, this); - this->leftOutputPublisher = n.advertise(leftTopicName + "/output", MESSAGE_CACHE_SIZE); - this->rightOutputPublisher = n.advertise(rightTopicName + "/output", MESSAGE_CACHE_SIZE); - this->leftFeedbackSubscriber = n.subscribe(leftTopicName + "/feeback", MESSAGE_CACHE_SIZE, &DifferentialJoint::handoffLeftFeedback, this); - this->rightFeedbackSubscriber = n.subscribe(rightTopicName + "/feeback", MESSAGE_CACHE_SIZE, &DifferentialJoint::handoffRightFeedback, this); - this->pitchFeedbackPublisher = n.advertise(pitchTopicName + "/feedback", MESSAGE_CACHE_SIZE); - this->rollFeedbackPublisher = n.advertise(rollTopicName + "/feedback", MESSAGE_CACHE_SIZE); -} - -auto DifferentialJoint::getJointPositions(const vector &motorPositions) -> vector{ - // vector positions; - // target->reserve(2); - - double pitch = motorPositions.at(0) * MOTOR_TO_JOINT_MATRIX.at(0).at(0) + motorPositions.at(1) * MOTOR_TO_JOINT_MATRIX.at(0).at(1); - double roll = motorPositions.at(0) * MOTOR_TO_JOINT_MATRIX.at(1).at(0) + motorPositions.at(1) * MOTOR_TO_JOINT_MATRIX.at(1).at(1); - - //TODO: Why not return a new vector? Wouldn't this constant resizing be more inefficient than just making/returning a new vector via copy ellision? - return {pitch, roll}; - - // return positions; -} - -auto DifferentialJoint::getMotorPositions(const vector &jointPositions) -> vector{ - - // std::unique_ptr> positions = std::make_unique>(2); - // target->reserve(2); - - double left = jointPositions.at(0) * JOINT_TO_MOTOR_MATRIX.at(0).at(0) + jointPositions.at(1) * JOINT_TO_MOTOR_MATRIX.at(0).at(1); - double right = jointPositions.at(0) * JOINT_TO_MOTOR_MATRIX.at(1).at(0) + jointPositions.at(1) * JOINT_TO_MOTOR_MATRIX.at(1).at(1); - - return {left, right}; - - // return std::move(positions); -} - -auto DifferentialJoint::getMotorVelocities(const vector &jointPositions) -> vector{ - return getMotorPositions(jointPositions); //deritivate of linear transformation is itself -} - -void DifferentialJoint::handoffPitchOutput(const std_msgs::Float64::ConstPtr &msg){ - this->cachedPitchOutput = msg->data; - this->hasNewPitchOutput = true; - handOffAllOutput(); -} -void DifferentialJoint::handoffRollOutput(const std_msgs::Float64::ConstPtr &msg){ - this->cachedRollOutput = msg->data; - this->hasNewRollOutput = true; - handOffAllOutput(); -} - -// TODO: Do these ouputs need to be synced? We're just referring to the motors individually, maybe we can transform and send the data right away -void DifferentialJoint::handOffAllOutput(){ - if(!this->hasNewPitchOutput || !this->hasNewRollOutput){ return; } - - vector outputs; - outputs.resize(2); - outputs.at(0) = this->cachedPitchOutput; - outputs.at(1) = this->cachedRollOutput; - //TODO: Still confused as to the purpose of this family of functions - outputs = getMotorVelocities(outputs); - - std_msgs::Float64 msg1; - std_msgs::Float64 msg2; - msg1.data = outputs.at(0); - msg2.data = outputs.at(1); - pitchFeedbackPublisher.publish(msg1); - rollFeedbackPublisher.publish(msg2); - - leftOutputPublisher.publish(msg1); - rightOutputPublisher.publish(msg2); - - this->hasNewPitchOutput = false; - this->hasNewRollOutput = false; - -} - -void DifferentialJoint::handoffRightFeedback(const std_msgs::Float64::ConstPtr &msg){ - this->cachedRightFeedback = msg->data; - this->hasNewRightFeedback = true; - handOffAllFeedback(); -} -void DifferentialJoint::handoffLeftFeedback(const std_msgs::Float64::ConstPtr &msg){ - this->cachedLeftFeedback = msg->data; - this->hasNewLeftFeedback = true; - handOffAllFeedback(); -} - -void DifferentialJoint::handOffAllFeedback(){ - if(!this->hasNewLeftFeedback || !this->hasNewRightFeedback){ return; } - - vector outputs; - outputs.at(0) = this->cachedLeftFeedback; - outputs.at(1) = this->cachedRightFeedback; - outputs = getMotorVelocities(outputs); - - std_msgs::Float64 msg1; - std_msgs::Float64 msg2; - msg1.data = outputs.at(0); - msg2.data = outputs.at(1); - pitchFeedbackPublisher.publish(msg1); - rollFeedbackPublisher.publish(msg2); - - this->hasNewLeftFeedback = false; - this->hasNewRightFeedback = false; - -} diff --git a/src/wr_control_drive_arm/src/DifferentialJoint.hpp b/src/wr_control_drive_arm/src/DifferentialJoint.hpp deleted file mode 100644 index 7bfaec4f..00000000 --- a/src/wr_control_drive_arm/src/DifferentialJoint.hpp +++ /dev/null @@ -1,56 +0,0 @@ -/** - * @file DifferentialJoint.hpp - * @author Nichols Underwood - * @brief Header file of the DifferentialJoint class - * @date 2021-10-25 - */ - -#include "AbstractJoint.hpp" - -class DifferentialJoint : public AbstractJoint { - public: - DifferentialJoint(std::unique_ptr leftMotor, std::unique_ptr rightMotor, ros::NodeHandle &n, - const std::string &pitchTopicName, const std::string &rollTopicName, - const std::string &leftTopicName, const std::string &rightTopicName); - - auto getMotorPositions(const vector &jointPositions) -> vector override; - auto getMotorVelocities(const vector &jointVelocities) -> vector override; - auto getJointPositions(const vector &motorPositions) -> vector override; - - private: - static constexpr uint32_t DEGREES_OF_FREEDOM = 2; - static constexpr uint32_t MESSAGE_CACHE_SIZE = 10; - // linear transformations works for position and velocity - // [0.5 0.5] [left motor ] [pitch] - // [ -1 1 ] * [right motor] = [roll ] - // double motorToJointMatrix[2][2] = {{0.5, 0.5}, {-1, 1}}; - static constexpr std::array, 2> MOTOR_TO_JOINT_MATRIX{{{1, 0}, {0, 1}}}; - // [1 -0.5] [pitch] [left motor ] - // [1 0.5] * [roll ] = [right motor] - // double jointToMotorMatrix[2][2] = {{1, 0.5}, {1, -0.5}}; - static constexpr std::array, 2> JOINT_TO_MOTOR_MATRIX{{{1, 0}, {0, 1}}}; - - void handoffPitchOutput(const std_msgs::Float64::ConstPtr&); - void handoffRollOutput(const std_msgs::Float64::ConstPtr&); - void handOffAllOutput(); - ros::Subscriber pitchOutputSubscriber; - ros::Subscriber rollOutputSubscriber; - ros::Publisher leftOutputPublisher; - ros::Publisher rightOutputPublisher; - float cachedPitchOutput = 0.0; - float cachedRollOutput = 0.0; - bool hasNewPitchOutput = false; - bool hasNewRollOutput = false; - - void handoffLeftFeedback(const std_msgs::Float64::ConstPtr&); - void handoffRightFeedback(const std_msgs::Float64::ConstPtr&); - void handOffAllFeedback(); - ros::Subscriber leftFeedbackSubscriber; - ros::Subscriber rightFeedbackSubscriber; - ros::Publisher pitchFeedbackPublisher; - ros::Publisher rollFeedbackPublisher; - float cachedLeftFeedback = 0.0; - float cachedRightFeedback = 0.0; - bool hasNewLeftFeedback = false; - bool hasNewRightFeedback = false; -}; \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.cpp b/src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.cpp new file mode 100644 index 00000000..dfe28450 --- /dev/null +++ b/src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.cpp @@ -0,0 +1,43 @@ +#include "DifferentialJointToMotorSpeedConverter.hpp" +#include + +DifferentialJointToMotorSpeedConverter::DifferentialJointToMotorSpeedConverter( + std::shared_ptr leftMotor, + std::shared_ptr rightMotor) + : cachedPitchSpeed{0}, + cachedRollSpeed{0}, + leftMotor{std::move(leftMotor)}, + rightMotor{std::move(rightMotor)} {} + +DifferentialJointToMotorSpeedConverter::DifferentialJointToMotorSpeedConverter( + const DifferentialJointToMotorSpeedConverter &other) + : cachedPitchSpeed{other.cachedPitchSpeed.load()}, + cachedRollSpeed{other.cachedRollSpeed.load()}, + leftMotor{other.leftMotor}, + rightMotor{other.rightMotor} {} + +DifferentialJointToMotorSpeedConverter::DifferentialJointToMotorSpeedConverter( + DifferentialJointToMotorSpeedConverter &&other) noexcept + : cachedPitchSpeed{other.cachedPitchSpeed.load()}, + cachedRollSpeed{other.cachedRollSpeed.load()}, + leftMotor{other.leftMotor}, + rightMotor{other.rightMotor} {} + +void DifferentialJointToMotorSpeedConverter::setPitchSpeed(double speed) { + cachedPitchSpeed = speed; + dispatchDifferentialSpeed(); +} + +void DifferentialJointToMotorSpeedConverter::setRollSpeed(double speed) { + cachedRollSpeed = speed; + dispatchDifferentialSpeed(); +} + +void DifferentialJointToMotorSpeedConverter::dispatchDifferentialSpeed() { + // const std::lock_guard guard{mutex}; + auto m1Speed{-cachedPitchSpeed + (cachedRollSpeed * AVERAGE_SCALING_FACTOR)}; + auto m2Speed{-cachedPitchSpeed - (cachedRollSpeed * AVERAGE_SCALING_FACTOR)}; + leftMotor->setSpeed(m1Speed); + rightMotor->setSpeed(m2Speed); + // std::cout << "ptch: " << cachedPitchSpeed.load() << "\troll: " << cachedRollSpeed.load() << "\tlspd: " << m1Speed << "\trspd: " << m2Speed << std::endl; +} \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.hpp b/src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.hpp new file mode 100644 index 00000000..5d096add --- /dev/null +++ b/src/wr_control_drive_arm/src/DifferentialJointToMotorSpeedConverter.hpp @@ -0,0 +1,31 @@ +#ifndef DIFFERENTIAL_JOINT_TO_MOTOR_SPEED_CONVERTER_H +#define DIFFERENTIAL_JOINT_TO_MOTOR_SPEED_CONVERTER_H + +#include "Motor.hpp" + +class DifferentialJointToMotorSpeedConverter { +public: + DifferentialJointToMotorSpeedConverter(std::shared_ptr leftMotor, std::shared_ptr rightMotor); + void setPitchSpeed(double speed); + void setRollSpeed(double speed); + + DifferentialJointToMotorSpeedConverter(const DifferentialJointToMotorSpeedConverter &); + auto operator=(const DifferentialJointToMotorSpeedConverter &) -> DifferentialJointToMotorSpeedConverter & = delete; + DifferentialJointToMotorSpeedConverter(DifferentialJointToMotorSpeedConverter &&) noexcept; + auto operator=(DifferentialJointToMotorSpeedConverter &&) -> DifferentialJointToMotorSpeedConverter & = delete; + ~DifferentialJointToMotorSpeedConverter() = default; + +private: + std::atomic cachedPitchSpeed; + std::atomic cachedRollSpeed; + std::recursive_mutex mutex; + + const std::shared_ptr leftMotor; + const std::shared_ptr rightMotor; + + static constexpr double AVERAGE_SCALING_FACTOR{1}; + + void dispatchDifferentialSpeed(); +}; + +#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp new file mode 100644 index 00000000..67fd0568 --- /dev/null +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp @@ -0,0 +1,18 @@ +#include "DirectJointToMotorSpeedConverter.hpp" + +DirectJointToMotorSpeedConverter::DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction) + : outputMotor{std::move(outputMotor)}, + direction{direction} {} + +void DirectJointToMotorSpeedConverter::operator()(double speed) { + double actualSpeed{0}; // In event of enum error, stop the motor + switch (direction) { + case MotorSpeedDirection::FORWARD: + actualSpeed = speed; + break; + case MotorSpeedDirection::REVERSE: + actualSpeed = -speed; + break; + } + outputMotor->setSpeed(actualSpeed); +} diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp new file mode 100644 index 00000000..6a117435 --- /dev/null +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp @@ -0,0 +1,28 @@ +#ifndef DIRECT_JOINT_TO_MOTOR_SPEED_CONVERTER_H +#define DIRECT_JOINT_TO_MOTOR_SPEED_CONVERTER_H + +#include "Motor.hpp" +#include + +enum class MotorSpeedDirection { + FORWARD, + REVERSE +}; + +class DirectJointToMotorSpeedConverter { +public: + DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction); + void operator()(double speed); + + DirectJointToMotorSpeedConverter(const DirectJointToMotorSpeedConverter &) = default; + auto operator=(const DirectJointToMotorSpeedConverter &) -> DirectJointToMotorSpeedConverter & = delete; + DirectJointToMotorSpeedConverter(DirectJointToMotorSpeedConverter &&) = default; + auto operator=(DirectJointToMotorSpeedConverter &&) -> DirectJointToMotorSpeedConverter & = delete; + ~DirectJointToMotorSpeedConverter() = default; + +private: + const MotorSpeedDirection direction; + const std::shared_ptr outputMotor; +}; + +#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/Joint.cpp b/src/wr_control_drive_arm/src/Joint.cpp new file mode 100644 index 00000000..08b7c8a3 --- /dev/null +++ b/src/wr_control_drive_arm/src/Joint.cpp @@ -0,0 +1,72 @@ +#include "Joint.hpp" +#include "MathUtil.hpp" +#include +#include + +using std::literals::string_literals::operator""s; +using MathUtil::RADIANS_PER_ROTATION; + +Joint::Joint(std::string name, + std::function positionMonitor, + std::function motorSpeedDispatcher, + ros::NodeHandle node) + : name{std::move(name)}, + positionMonitor{std::move(positionMonitor)}, + motorSpeedDispatcher{std::move(motorSpeedDispatcher)}, + executeMotion{false}, + controlLoopUpdateTimer{node.createTimer(ros::Rate{FEEDBACK_UPDATE_FREQUENCY_HZ}, &Joint::onFeedbackUpdateEvent, this, false, false)}, + controlLoopOutputSubscriber{node.subscribe("/control/arm/pid/"s + this->name + "/output", 1, &Joint::onControlLoopOutput, this)}, + controlLoopSetpointPublisher{node.advertise("/control/arm/pid/"s + this->name + "/setpoint", 1)}, + controlLoopFeedbackPublisher{node.advertise("/control/arm/pid/"s + this->name + "/feedback", 1)} {} + +void Joint::setTarget(double target, double maxSpeed) { + this->target = target; + this->maxSpeed = maxSpeed; + executeMotion = true; + controlLoopUpdateTimer.start(); +} + +auto Joint::hasReachedTarget() const -> bool { + // Copy-on-read to avoid inconsistencies on asynchronous change + auto currentTarget = target.load(); + + // Compute the upper and lower bounds in the finite encoder space + auto lBound = MathUtil::corrMod(currentTarget - JOINT_TOLERANCE_RADIANS, RADIANS_PER_ROTATION); + auto uBound = MathUtil::corrMod(currentTarget + JOINT_TOLERANCE_RADIANS, RADIANS_PER_ROTATION); + auto position = MathUtil::corrMod(positionMonitor(), RADIANS_PER_ROTATION); + // If the computed lower bound is lower than the upper bound, perform the computation normally + if (lBound < uBound) + return position <= uBound && position >= lBound; + // Otherwise, check if the value is outside either bound and negate the response + return position <= uBound || position >= lBound; +} + +auto Joint::getName() const -> std::string { + return name; +} + +void Joint::stop() { + executeMotion = false; + controlLoopUpdateTimer.stop(); + motorSpeedDispatcher(0); +} + +void Joint::onControlLoopOutput(const std_msgs::Float64::ConstPtr &msg) { + auto cappedPowerUnsigned{std::min(std::abs(msg->data), std::abs(maxSpeed))}; + double cappedPower{0}; + if (msg->data != 0) + cappedPower = (std::abs(msg->data) / msg->data) * cappedPowerUnsigned; + motorSpeedDispatcher(executeMotion ? cappedPower : 0); +} + +void Joint::onFeedbackUpdateEvent(const ros::TimerEvent &event) { + // Setpoint + std_msgs::Float64 setpointMsg; + setpointMsg.data = target; + controlLoopSetpointPublisher.publish(setpointMsg); + + // Feedback + std_msgs::Float64 feedbackMsg; + feedbackMsg.data = positionMonitor(); + controlLoopFeedbackPublisher.publish(feedbackMsg); +} \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/Joint.hpp b/src/wr_control_drive_arm/src/Joint.hpp new file mode 100644 index 00000000..659a4f98 --- /dev/null +++ b/src/wr_control_drive_arm/src/Joint.hpp @@ -0,0 +1,39 @@ +#ifndef JOINT_H +#define JOINT_H + +#include "ros/publisher.h" +#include "ros/subscriber.h" +#include "ros/timer.h" +#include "std_msgs/Float64.h" +#include +#include + +class Joint { +public: + explicit Joint(std::string name, std::function positionMonitor, std::function motorSpeedDispatcher, ros::NodeHandle node); + void setTarget(double target, double maxSpeed); + [[nodiscard]] auto hasReachedTarget() const -> bool; + [[nodiscard]] auto getName() const -> std::string; + void stop(); + +private: + static constexpr double FEEDBACK_UPDATE_FREQUENCY_HZ{50}; + static constexpr double JOINT_TOLERANCE_RADIANS{3 * M_PI / 180}; + + const std::string name; + const std::function positionMonitor; + const std::function motorSpeedDispatcher; + + void onControlLoopOutput(const std_msgs::Float64::ConstPtr &msg); + void onFeedbackUpdateEvent(const ros::TimerEvent &event); + + std::atomic target; + std::atomic maxSpeed; + std::atomic executeMotion; + ros::Timer controlLoopUpdateTimer; + ros::Subscriber controlLoopOutputSubscriber; + ros::Publisher controlLoopSetpointPublisher; + ros::Publisher controlLoopFeedbackPublisher; +}; + +#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/JointStatePublisher.cpp b/src/wr_control_drive_arm/src/JointStatePublisher.cpp index 3638c4ff..3a93cba6 100644 --- a/src/wr_control_drive_arm/src/JointStatePublisher.cpp +++ b/src/wr_control_drive_arm/src/JointStatePublisher.cpp @@ -5,12 +5,10 @@ * @brief The executable file to run the joint state publisher * @date 2022-12-05 */ + +#include "SingleEncoderJointPositionMonitor.hpp" #include "XmlRpcValue.h" -#include "DifferentialJoint.hpp" -#include "SimpleJoint.hpp" -#include "ros/console.h" -#include "ros/ros.h" #include #include #include @@ -28,34 +26,28 @@ using XmlRpc::XmlRpcValue; /** * @brief Nessage cache size of publisher */ -constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1000; +constexpr std::uint32_t MESSAGE_CACHE_SIZE = 1; /** * @brief Period between timer callback */ constexpr float TIMER_CALLBACK_DURATION = 1.0 / 50.0; -/** - * @brief Defines space for all Joint references - */ -constexpr int NUM_JOINTS = 5; -std::array, NUM_JOINTS> joints; - /** * @brief The joint state publisher for MoveIt */ ros::Publisher jointStatePublisher; +std::map namedJointPositionMonitors; + void publishJointStates(const ros::TimerEvent &event) { std::vector names; std::vector positions; sensor_msgs::JointState js_msg; - for (const auto &joint : joints) { - for (int i = 0; i < joint->getDegreesOfFreedom(); i++) { - names.push_back(joint->getMotor(i)->getMotorName()); - positions.push_back(joint->getMotor(i)->getRads()); - } + for (auto &[name, monitor] : namedJointPositionMonitors) { + names.push_back(name); + positions.push_back(monitor()); } js_msg.name = names; @@ -65,6 +57,11 @@ void publishJointStates(const ros::TimerEvent &event) { jointStatePublisher.publish(js_msg); } +auto getEncoderConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> EncoderConfiguration { + return {.countsPerRotation = static_cast(params[jointName]["counts_per_rotation"]), + .offset = static_cast(params[jointName]["offset"])}; +} + /** * @brief The main executable method of the node. Starts the ROS node * @@ -75,31 +72,50 @@ void publishJointStates(const ros::TimerEvent &event) { auto main(int argc, char **argv) -> int { std::cout << "start main" << std::endl; - // Initialize the current node as JointStatePublisherApplication + // // Initialize the current node as JointStatePublisherApplication ros::init(argc, argv, "JointStatePublisher"); - // Create the NodeHandle to the current ROS node + // // Create the NodeHandle to the current ROS node ros::NodeHandle n; ros::NodeHandle pn{"~"}; XmlRpcValue encParams; pn.getParam("encoder_parameters", encParams); - // Initialize all motors with their MoveIt name, WRoboclaw initialization, and reference to the current node - auto elbowPitch_joint = std::make_unique("elbowPitch_joint", 1, 0, static_cast(encParams[0]["counts_per_rotation"]), static_cast(encParams[0]["offset"]), n, true); - auto elbowRoll_joint = std::make_unique("elbowRoll_joint", 1, 1, static_cast(encParams[1]["counts_per_rotation"]), static_cast(encParams[1]["offset"]), n, true); - auto shoulder_joint = std::make_unique("shoulder_joint", 0, 1, static_cast(encParams[2]["counts_per_rotation"]), static_cast(encParams[2]["offset"]), n, true); - auto turntable_joint = std::make_unique("turntable_joint", 0, 0, static_cast(encParams[3]["counts_per_rotation"]), static_cast(encParams[3]["offset"]), n, true); - auto wristPitch_joint = std::make_unique("wristPitch_joint", 2, 0, static_cast(encParams[4]["counts_per_rotation"]), static_cast(encParams[4]["offset"]), n, true); - auto wristRoll_link = std::make_unique("wristRoll_link", 2, 1, static_cast(encParams[5]["counts_per_rotation"]), static_cast(encParams[5]["offset"]), n, true); - std::cout << "init motors" << std::endl; - - // Initialize all Joints - joints.at(0) = std::make_unique(std::move(elbowPitch_joint), n); - joints.at(1) = std::make_unique(std::move(elbowRoll_joint), n); - joints.at(2) = std::make_unique(std::move(shoulder_joint), n); - joints.at(3) = std::make_unique(std::move(turntable_joint), n); - joints.at(4) = std::make_unique(std::move(wristPitch_joint), std::move(wristRoll_link), n, "/control/arm/5/pitch", "/control/arm/5/roll", "/control/arm/20/", "/control/arm/21/"); - std::cout << "init joints" << std::endl; + namedJointPositionMonitors.try_emplace("elbowPitch_joint", + + "aux1", + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "elbow"), + n); + namedJointPositionMonitors.try_emplace("elbowRoll_joint", + + "aux1", + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "forearmRoll"), + n); + namedJointPositionMonitors.try_emplace("shoulder_joint", + + "aux0", + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "shoulder"), + n); + namedJointPositionMonitors.try_emplace("turntable_joint", + + "aux0", + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "turntable"), + n); + namedJointPositionMonitors.try_emplace("wristPitch_joint", + + "aux2", + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "wristPitch"), + n); + namedJointPositionMonitors.try_emplace("wristRoll_link", + "aux2", + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "wristRoll"), + n); // Initialize the Joint State Data Publisher jointStatePublisher = n.advertise("/joint_states", MESSAGE_CACHE_SIZE); diff --git a/src/wr_control_drive_arm/src/MathUtil.cpp b/src/wr_control_drive_arm/src/MathUtil.cpp new file mode 100644 index 00000000..682b0bad --- /dev/null +++ b/src/wr_control_drive_arm/src/MathUtil.cpp @@ -0,0 +1,8 @@ +#include "MathUtil.hpp" +#include + +namespace MathUtil { +auto corrMod(double dividend, double divisor) -> double { + return std::fmod(std::fmod(dividend, divisor) + divisor, std::abs(divisor)); +} +} // namespace MathUtil \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/MathUtil.hpp b/src/wr_control_drive_arm/src/MathUtil.hpp new file mode 100644 index 00000000..07e7b0d0 --- /dev/null +++ b/src/wr_control_drive_arm/src/MathUtil.hpp @@ -0,0 +1,11 @@ +#ifndef MATH_UTIL_H +#define MATH_UTIL_H + +#include + +namespace MathUtil { +auto corrMod(double dividend, double divisor) -> double; +static constexpr double RADIANS_PER_ROTATION{2 * M_PI}; +} // namespace MathUtil + +#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/Motor.cpp b/src/wr_control_drive_arm/src/Motor.cpp new file mode 100644 index 00000000..bc96cd0f --- /dev/null +++ b/src/wr_control_drive_arm/src/Motor.cpp @@ -0,0 +1,45 @@ +#include "Motor.hpp" +#include "RoboclawChannel.hpp" +#include "ros/node_handle.h" +#include "ros/time.h" +#include "std_msgs/Int16.h" +#include +#include +#include +#include + +using std::literals::string_literals::operator""s; + +Motor::Motor(const std::string &controllerName, RoboclawChannel channel, ros::NodeHandle node) + : motorSpeedPublisher{ + node.advertise( + "/hsi/roboclaw/"s + controllerName + "/cmd/"s + (channel == RoboclawChannel::A ? "left" : "right"), + 1)}, + currentOverLimitSubscriber{ + node.subscribe("/hsi/roboclaw/"s + controllerName + "/curr/over_lim/" + (channel == RoboclawChannel::A ? "left" : "right"), + OVER_CURRENT_QUEUE_SIZE, &Motor::setCurrentStatus, this)} {} + +void Motor::setSpeed(double speed) { + if (abs(speed) > 1) + throw std::invalid_argument("speed must be between -1 and 1"); + + std_msgs::Int16 powerMsg{}; + powerMsg.data = static_cast(speed * INT16_MAX); + motorSpeedPublisher.publish(powerMsg); +} + +void Motor::setCurrentStatus(const std_msgs::Bool::ConstPtr &msg) { + bool overCurrent = static_cast(msg->data); + if (overCurrent && !this->beginStallTime.has_value()) { + this->beginStallTime = ros::Time::now(); + } else if (!overCurrent && this->beginStallTime.has_value()) { + this->beginStallTime = std::nullopt; + } +} + +auto Motor::isOverCurrent() const -> bool { + if (this->beginStallTime.has_value()) { + return static_cast((ros::Time::now() - this->beginStallTime.value()).toSec() >= STALL_THRESHOLD_TIME); + } + return false; +} diff --git a/src/wr_control_drive_arm/src/Motor.hpp b/src/wr_control_drive_arm/src/Motor.hpp new file mode 100644 index 00000000..ff3a6174 --- /dev/null +++ b/src/wr_control_drive_arm/src/Motor.hpp @@ -0,0 +1,30 @@ +#ifndef MOTOR_H +#define MOTOR_H + +#include "RoboclawChannel.hpp" +#include "ros/publisher.h" +#include "ros/subscriber.h" +#include "std_msgs/Bool.h" +#include +#include + +class Motor { +public: + Motor(const std::string &controllerName, RoboclawChannel channel, ros::NodeHandle node); + void setSpeed(double speed); + auto isOverCurrent() const -> bool; + +private: + + static constexpr float STALL_THRESHOLD_TIME{0.5F}; + static constexpr int OVER_CURRENT_QUEUE_SIZE{25}; + + + void setCurrentStatus(const std_msgs::Bool::ConstPtr &msg); + + ros::Publisher motorSpeedPublisher; + ros::Subscriber currentOverLimitSubscriber; + std::optional beginStallTime; +}; + +#endif diff --git a/src/wr_control_drive_arm/src/RoboclawChannel.hpp b/src/wr_control_drive_arm/src/RoboclawChannel.hpp new file mode 100644 index 00000000..fbf7de00 --- /dev/null +++ b/src/wr_control_drive_arm/src/RoboclawChannel.hpp @@ -0,0 +1,6 @@ +#ifndef ROBOCLAW_CHANNEL_H +#define ROBOCLAW_CHANNEL_H + +enum class RoboclawChannel { A, B }; + +#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/SimpleJoint.cpp b/src/wr_control_drive_arm/src/SimpleJoint.cpp deleted file mode 100644 index d7ca2ee2..00000000 --- a/src/wr_control_drive_arm/src/SimpleJoint.cpp +++ /dev/null @@ -1,24 +0,0 @@ -/** - * @file SimpleJoint.cpp - * @author Nichols Underwood - * @brief Implementation of the SimpleJoint class - * @date 2021-10-25 - */ - -#include "SimpleJoint.hpp" - -SimpleJoint::SimpleJoint(std::unique_ptr motor, ros::NodeHandle &n) : AbstractJoint(n, 1) { - this->motors.at(0) = MotorHandler{std::move(motor), 0, 0, "", "", false}; -} - -auto SimpleJoint::getMotorPositions(const vector &jointPositions) -> vector { - return {jointPositions[0]}; -} - -auto SimpleJoint::getMotorVelocities(const vector &jointVelocities) -> vector { - return {jointVelocities[0]}; -} - -auto SimpleJoint::getJointPositions(const vector &jointPositions) -> vector { - return {jointPositions[0]}; -} \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/SimpleJoint.hpp b/src/wr_control_drive_arm/src/SimpleJoint.hpp deleted file mode 100644 index 2c1bf76b..00000000 --- a/src/wr_control_drive_arm/src/SimpleJoint.hpp +++ /dev/null @@ -1,18 +0,0 @@ -/** - * @file SimpleJoint.hpp - * @author Nichols Underwood - * @brief Header file of the SimpleJoint class - * @date 2021-10-25 - */ - -#include "AbstractJoint.hpp" - -using std::vector; - -class SimpleJoint : public AbstractJoint { - public: - SimpleJoint(std::unique_ptr motor, ros::NodeHandle& n); - auto getMotorPositions(const vector &jointPositions) -> vector override; - auto getMotorVelocities(const vector &joinVelocities) -> vector override; - auto getJointPositions(const vector &motorPositions) -> vector override; -}; diff --git a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp new file mode 100644 index 00000000..9c179dc8 --- /dev/null +++ b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp @@ -0,0 +1,46 @@ +#include "SingleEncoderJointPositionMonitor.hpp" +#include "MathUtil.hpp" +#include "RoboclawChannel.hpp" +#include "ros/node_handle.h" + +using std::literals::string_literals::operator""s; +using MathUtil::RADIANS_PER_ROTATION; + +SingleEncoderJointPositionMonitor::SingleEncoderJointPositionMonitor( + const std::string &controllerName, + RoboclawChannel channel, + EncoderConfiguration config, + ros::NodeHandle node) + : countsPerRotation{config.countsPerRotation}, + offset{config.offset}, + position{0}, + encoderSubscriber{ + std::make_shared(node.subscribe( + "/hsi/roboclaw/"s + controllerName + "/enc/" + (channel == RoboclawChannel::A ? "left" : "right"), + 1, + &SingleEncoderJointPositionMonitor::onEncoderReceived, + this))} {} + +SingleEncoderJointPositionMonitor::SingleEncoderJointPositionMonitor( + const SingleEncoderJointPositionMonitor &other) + : countsPerRotation(other.countsPerRotation), + offset(other.offset), + encoderSubscriber{other.encoderSubscriber}, + position{other.position.load()} {} + +SingleEncoderJointPositionMonitor::SingleEncoderJointPositionMonitor( + SingleEncoderJointPositionMonitor &&other) noexcept + : countsPerRotation(other.countsPerRotation), + offset(other.offset), + encoderSubscriber{std::move(other.encoderSubscriber)}, + position{other.position.load()} {} + +auto SingleEncoderJointPositionMonitor::operator()() -> double { + return position; +} + +void SingleEncoderJointPositionMonitor::onEncoderReceived(const std_msgs::UInt32::ConstPtr &msg) { + auto enc = static_cast(msg->data); + auto rotations = MathUtil::corrMod(enc - offset, countsPerRotation) / countsPerRotation; + position = MathUtil::corrMod(rotations * RADIANS_PER_ROTATION + M_PI, RADIANS_PER_ROTATION) - M_PI; +} diff --git a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp new file mode 100644 index 00000000..cdf9938e --- /dev/null +++ b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp @@ -0,0 +1,36 @@ +#ifndef SINGLE_ENCODER_JOINT_POSITION_MONITOR_H +#define SINGLE_ENCODER_JOINT_POSITION_MONITOR_H + +#include "RoboclawChannel.hpp" +#include +#include +#include +#include +#include + +struct EncoderConfiguration { + int32_t countsPerRotation; + int32_t offset; +}; + +class SingleEncoderJointPositionMonitor { +public: + SingleEncoderJointPositionMonitor(const std::string &controllerName, RoboclawChannel channel, EncoderConfiguration config, ros::NodeHandle node); + auto operator()() -> double; + + SingleEncoderJointPositionMonitor(const SingleEncoderJointPositionMonitor &); + auto operator=(const SingleEncoderJointPositionMonitor &) -> SingleEncoderJointPositionMonitor & = delete; + SingleEncoderJointPositionMonitor(SingleEncoderJointPositionMonitor &&) noexcept; + auto operator=(SingleEncoderJointPositionMonitor &&) -> SingleEncoderJointPositionMonitor & = delete; + ~SingleEncoderJointPositionMonitor() = default; + +private: + void onEncoderReceived(const std_msgs::UInt32::ConstPtr &msg); + + std::atomic position; + std::shared_ptr encoderSubscriber; + const int32_t countsPerRotation; + const int32_t offset; +}; + +#endif \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/testDifferential.cpp b/src/wr_control_drive_arm/src/testDifferential.cpp new file mode 100644 index 00000000..5b2d31a6 --- /dev/null +++ b/src/wr_control_drive_arm/src/testDifferential.cpp @@ -0,0 +1,26 @@ +#include +#include "Motor.hpp" +#include "DifferentialJointToMotorSpeedConverter.hpp" +#include "ros/init.h" +#include + +auto main(int32_t argc, char** argv) -> int32_t{ + ros::init(argc, argv, "testNode"); + + ros::NodeHandle n{}; + using std::literals::string_literals::operator""s; + + const auto wristLeftMotor{std::make_shared("aux2"s, RoboclawChannel::A, n)}; + const auto wristRightMotor{std::make_shared("aux2"s, RoboclawChannel::B, n)}; + + const auto differentialSpeedConverter{std::make_shared(wristLeftMotor, wristRightMotor)}; + + ros::Rate loopRate{50}; + while(ros::ok()){ + differentialSpeedConverter->setPitchSpeed(0.3); + differentialSpeedConverter->setRollSpeed(0); + loopRate.sleep(); + } + + return 0; +} \ No newline at end of file diff --git a/src/wr_entry_point/launch/test/mock_arm.launch b/src/wr_entry_point/launch/test/mock_arm.launch index 67abb1df..6dfbb8b1 100644 --- a/src/wr_entry_point/launch/test/mock_arm.launch +++ b/src/wr_entry_point/launch/test/mock_arm.launch @@ -1,21 +1,24 @@ - - - - + + + + + + + - - - - + + + + - - - - - - - - + + + + + + + + \ No newline at end of file diff --git a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp index 5c1b684e..9cdbb880 100644 --- a/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp +++ b/src/wr_logic_teleop_arm/src/ArmTeleopLogic.cpp @@ -1,3 +1,4 @@ +#include "boost/function.hpp" #include "geometry_msgs/PoseStamped.h" #include "geometry_msgs/Quaternion.h" #include "moveit_msgs/RobotTrajectory.h" @@ -5,26 +6,25 @@ #include "ros/subscriber.h" #include "std_msgs/Bool.h" #include "std_msgs/Float32.h" -#include "boost/function.hpp" #include "tf2/LinearMath/Quaternion.h" #include "tf2/LinearMath/Vector3.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.h" #include #include #include -#include #include #include +#include #include -using Std_Bool = const std_msgs::BoolConstPtr&; -using Std_Float32 = const std_msgs::Float32ConstPtr&; +using Std_Bool = const std_msgs::BoolConstPtr &; +using Std_Float32 = const std_msgs::Float32ConstPtr &; -std::atomic_bool isNewPath { true }; -const tf2::Quaternion WORLD_OFFSET {0, sin(M_PI/2), 0, cos(M_PI/2)}; +std::atomic_bool isNewPath{true}; +const tf2::Quaternion WORLD_OFFSET{0, sin(M_PI / 2), 0, cos(M_PI / 2)}; -auto updateTarget(float x_pos, float y_pos, float z_pos, tf2::Quaternion orientation, ros::Publisher &pub) -> void{ - geometry_msgs::PoseStamped p {}; +auto updateTarget(float x_pos, float y_pos, float z_pos, tf2::Quaternion orientation, ros::Publisher &pub) -> void { + geometry_msgs::PoseStamped p{}; p.pose.position.x = x_pos; p.pose.position.y = y_pos; p.pose.position.z = z_pos; @@ -34,15 +34,15 @@ auto updateTarget(float x_pos, float y_pos, float z_pos, tf2::Quaternion orienta pub.publish(p); } -auto main(int argc, char** argv) -> int{ +auto main(int argc, char **argv) -> int { ros::init(argc, argv, "ArmTeleopLogic"); ros::AsyncSpinner spin(1); spin.start(); - ros::NodeHandle np("~"); + ros::NodeHandle np("~"); constexpr float PLANNING_TIME = 0.05; constexpr float CLOCK_RATE = 2; - constexpr uint32_t MESSAGE_QUEUE_LENGTH = 1000; + constexpr uint32_t MESSAGE_QUEUE_LENGTH = 1000; constexpr float TRIGGER_PRESSED = 0.5; constexpr float JOYSTICK_DEADBAND = 0.1; constexpr float MINIMUM_PATH_ACCURACY = 0.0; @@ -55,7 +55,6 @@ auto main(int argc, char** argv) -> int{ constexpr float HOME_Y = -0.7; constexpr float HOME_Z = 0.2; - float accel = 1.0; float deaccel = 1.0; float step_mult = 1.0; @@ -63,171 +62,160 @@ auto main(int argc, char** argv) -> int{ float y_pos = HOME_Y; float z_pos = HOME_Z; - tf2::Quaternion orientation {sin(M_PI/4), 0, 0, cos(-M_PI/4)}; + tf2::Quaternion orientation{sin(M_PI / 4), 0, 0, cos(-M_PI / 4)}; orientation = orientation; - const tf2::Quaternion SPIN_X {sin(2*M_PI/1000), 0, 0, cos(2*M_PI/1000)}; - const tf2::Quaternion SPIN_Y {0, sin(2*M_PI/1000), 0, cos(2*M_PI/1000)}; - const tf2::Quaternion SPIN_Z {0, 0, sin(2*M_PI/1000), cos(2*M_PI/1000)}; + const tf2::Quaternion SPIN_X{sin(2 * M_PI / 1000), 0, 0, cos(2 * M_PI / 1000)}; + const tf2::Quaternion SPIN_Y{0, sin(2 * M_PI / 1000), 0, cos(2 * M_PI / 1000)}; + const tf2::Quaternion SPIN_Z{0, 0, sin(2 * M_PI / 1000), cos(2 * M_PI / 1000)}; moveit::planning_interface::MoveGroupInterface move("arm"); // move.setPlannerId("RRTStar"); move.setPlanningTime(PLANNING_TIME); - const moveit::core::JointModelGroup* joint_model_group = move.getCurrentState()->getJointModelGroup("arm"); + const moveit::core::JointModelGroup *joint_model_group = move.getCurrentState()->getJointModelGroup("arm"); robot_state::RobotState start_state(*move.getCurrentState()); moveit_visual_tools::MoveItVisualTools visual_tools("arm"); + ros::Rate loop{CLOCK_RATE}; - ros::Rate loop {CLOCK_RATE}; + ros::Publisher nextTarget = np.advertise("/logic/arm_teleop/next_target", + MESSAGE_QUEUE_LENGTH); - ros::Publisher nextTarget = np.advertise("/logic/arm_teleop/next_target", - MESSAGE_QUEUE_LENGTH); - - ros::Publisher trajectoryPub = np.advertise("/logic/arm_teleop/trajectory", - MESSAGE_QUEUE_LENGTH); - + ros::Publisher trajectoryPub = np.advertise("/logic/arm_teleop/trajectory", + MESSAGE_QUEUE_LENGTH); // y axis - ros::Subscriber yAxis = np.subscribe("/hci/arm/gamepad/axis/stick_left_y", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Float32 msg) -> void { - if(abs(msg->data) >= JOYSTICK_DEADBAND){ - y_pos += msg->data * STEP_Y; - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + ros::Subscriber yAxis = np.subscribe("/hci/arm/gamepad/axis/stick_left_y", + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Float32 msg) -> void { + if (abs(msg->data) >= JOYSTICK_DEADBAND) { + y_pos += msg->data * STEP_Y; + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); // x axis - ros::Subscriber xAxis = np.subscribe("/hci/arm/gamepad/axis/stick_left_x", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Float32 msg) -> void { - if(abs(msg->data) >= JOYSTICK_DEADBAND){ - x_pos += msg->data * STEP_X; - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + ros::Subscriber xAxis = np.subscribe("/hci/arm/gamepad/axis/stick_left_x", + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Float32 msg) -> void { + if (abs(msg->data) >= JOYSTICK_DEADBAND) { + x_pos += msg->data * STEP_X; + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); // y up ros::Subscriber zUp = np.subscribe("/hci/arm/gamepad/button/shoulder_l", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Bool msg) -> void { - if(msg->data){ - z_pos += STEP_Y * step_mult; - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Bool msg) -> void { + if (msg->data) { + z_pos += STEP_Y * step_mult; + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); // y down ros::Subscriber zDown = np.subscribe("/hci/arm/gamepad/button/shoulder_r", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Bool msg) -> void { - if(msg->data){ - z_pos -= STEP_Y * step_mult; - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); - - //roll counter clockwise + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Bool msg) -> void { + if (msg->data) { + z_pos -= STEP_Y * step_mult; + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); + + // roll counter clockwise ros::Subscriber rollUp = np.subscribe("/hci/arm/gamepad/button/y", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Bool msg) -> void { - if(msg->data){ - orientation *= SPIN_Z * step_mult; - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Bool msg) -> void { + if (msg->data) { + orientation *= SPIN_Z * step_mult; + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); // roll clockwise ros::Subscriber rollDown = np.subscribe("/hci/arm/gamepad/button/a", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Bool msg) -> void { - if(msg->data){ - orientation *= SPIN_Z.inverse(); - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Bool msg) -> void { + if (msg->data) { + orientation *= SPIN_Z.inverse(); + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); // pitch ros::Subscriber pitch = np.subscribe("/hci/arm/gamepad/axis/stick_right_y", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Float32 msg) -> void { - if(abs(msg->data) >= 0.5){ - orientation *= (msg->data > 0 ? SPIN_Y : SPIN_Y.inverse()); - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Float32 msg) -> void { + if (abs(msg->data) >= 0.5) { + orientation *= (msg->data > 0 ? SPIN_Y : SPIN_Y.inverse()); + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); // yaw ros::Subscriber yaw = np.subscribe("/hci/arm/gamepad/axis/stick_right_x", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Float32 msg) -> void { - if(abs(msg->data) >= 0.5){ - orientation *= (msg->data > 0 ? SPIN_X : SPIN_X.inverse()); - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - isNewPath.store(true); - - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Float32 msg) -> void { + if (abs(msg->data) >= 0.5) { + orientation *= (msg->data > 0 ? SPIN_X : SPIN_X.inverse()); + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); + } + })); ros::Subscriber speedUp = np.subscribe("/hci/arm/gamepad/axis/trigger_right", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Float32 msg) -> void { - accel = msg->data; - step_mult = std::pow(10,accel-deaccel); - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Float32 msg) -> void { + accel = msg->data; + step_mult = std::pow(10, accel - deaccel); + })); ros::Subscriber speedDown = np.subscribe("/hci/arm/gamepad/axis/trigger_right", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Float32 msg) -> void { - deaccel = msg->data; - step_mult = std::pow(10,accel-deaccel); - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Float32 msg) -> void { + deaccel = msg->data; + step_mult = std::pow(10, accel - deaccel); + })); // override path execution ros::Subscriber execPath = np.subscribe("/hci/arm/gamepad/button/x", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Bool msg) -> void { - if(msg->data){ - isNewPath.store(true); - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Bool msg) -> void { + if (msg->data) { + isNewPath.store(true); + } + })); // reset target/cancel path ros::Subscriber resetPose = np.subscribe("/hci/arm/gamepad/button/start", - MESSAGE_QUEUE_LENGTH, - static_cast>([&](Std_Bool msg) -> void { - if(msg->data){ - - geometry_msgs::Pose pose = move.getCurrentPose().pose; - x_pos = pose.position.x; - y_pos = pose.position.y; - z_pos = pose.position.z; - tf2::convert(pose.orientation, orientation); - updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - - isNewPath.store(true); //override path - } - })); + MESSAGE_QUEUE_LENGTH, + static_cast>([&](Std_Bool msg) -> void { + if (msg->data) { + + geometry_msgs::Pose pose = move.getCurrentPose().pose; + x_pos = pose.position.x; + y_pos = pose.position.y; + z_pos = pose.position.z; + tf2::convert(pose.orientation, orientation); + updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); + isNewPath.store(true); // override path + } + })); - while(ros::ok()){ + while (ros::ok()) { updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - if(!isNewPath.load()){ + if (!isNewPath.load()) { loop.sleep(); continue; } @@ -237,7 +225,7 @@ auto main(int argc, char** argv) -> int{ move.stop(); // configure target pose - geometry_msgs::PoseStamped p {}; + geometry_msgs::PoseStamped p{}; p.pose.position.x = x_pos; p.pose.position.y = y_pos; p.pose.position.z = z_pos; @@ -247,25 +235,25 @@ auto main(int argc, char** argv) -> int{ move.setPoseTarget(p); move.setStartStateToCurrentState(); - //plan and execute path + // plan and execute path move.asyncMove(); - while(ros::ok()){ + while (ros::ok()) { updateTarget(x_pos, y_pos, z_pos, orientation, nextTarget); - if(move.getMoveGroupClient().getState().isDone()){ + if (move.getMoveGroupClient().getState().isDone()) { std::cout << "[INFO] [" << ros::Time::now() << "]: path finished: " << move.getMoveGroupClient().getState().getText() << std::endl; break; - } - - else if(isNewPath.load()){ + } + + else if (isNewPath.load()) { std::cout << "[INFO] [" << ros::Time::now() << "]: path overridden" << std::endl; move.stop(); break; } loop.sleep(); - } + } } return 0; diff --git a/src/wroboarm_23/config/joint_limits.yaml b/src/wroboarm_23/config/joint_limits.yaml index 1935df40..ae579b8e 100644 --- a/src/wroboarm_23/config/joint_limits.yaml +++ b/src/wroboarm_23/config/joint_limits.yaml @@ -13,36 +13,36 @@ joint_limits: max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 - max_position: !radians pi - min_position: !radians 0 + max_position: !radians 2.2 + min_position: !radians -0.2 elbowRoll_joint: has_velocity_limits: true max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 - max_position: !radians pi / 2 - min_position: !radians -pi / 2 + max_position: !radians 0.7 + min_position: !radians -0.7 shoulder_joint: has_velocity_limits: true max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 max_position: !radians 0 - min_position: !radians -pi + min_position: !radians -1.3 turntable_joint: has_velocity_limits: true max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 - max_position: !radians pi - min_position: !radians -pi + max_position: !radians pi / 2 + min_position: !radians 0 wristPitch_joint: has_velocity_limits: true max_velocity: 10 has_acceleration_limits: true max_acceleration: 10 - max_position: !radians pi - min_position: !radians 0 + max_position: !radians 2.5 + min_position: !radians -2.5 wristRoll_link: has_velocity_limits: true max_velocity: 10 diff --git a/testscrpt.py b/testscrpt.py new file mode 100755 index 00000000..dd6cb4c3 --- /dev/null +++ b/testscrpt.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python3 +import rospy +import sensor_msgs.msg as sensor_msgs +import matplotlib.pyplot as plt +from threading import Thread + +positions = None +names = None + +def newJS(jsMsg: sensor_msgs.JointState): + global positions, names + if positions is None: + positions = [] + names = [name for name in jsMsg.name] + for pos in jsMsg.position: + positions.append([pos]) + else: + for l, pos in zip(positions, jsMsg.position): + l.append(pos) + if len(l) > 500: + del l[0] + +def plot(): + global positions, names + while not rospy.is_shutdown(): + if positions is not None and names is not None: + for l in positions: + plt.plot(l) + plt.legend(names) + plt.pause(0.05) + plt.clf() + + +if __name__=="__main__": + rospy.init_node("testNode") + sub = rospy.Subscriber("/joint_states", sensor_msgs.JointState, newJS) + t1 = Thread(target=plot) + t1.start() + t1.join() + rospy.spin() + \ No newline at end of file From b5ba58849ac6bdf12ff8ef8a27746c2fa6813dbd Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Wed, 8 Mar 2023 19:03:50 -0600 Subject: [PATCH 23/33] Added implementation for scaling joint speeds based on gear ratios --- .../src/ArmControlActionServer.cpp | 94 +++++++++++-------- .../src/SingleEncoderJointPositionMonitor.cpp | 5 + .../src/SingleEncoderJointPositionMonitor.hpp | 2 + 3 files changed, 61 insertions(+), 40 deletions(-) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 14892cd3..41769b72 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include @@ -57,6 +58,8 @@ constexpr float TIMER_CALLBACK_DURATION{1.0 / 50.0}; */ std::unordered_map> namedJointMap; +std::unordered_map> namedPositionMonitors; + /** * @brief Simplify the SimpleActionServer reference name */ @@ -110,17 +113,23 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, return; } + std::vector velocityCopies{currTargetPosition.velocities}; + + for (uint32_t i = 0; i < goal->trajectory.joint_names.size(); ++i) { + velocityCopies.at(i) *= abs(namedPositionMonitors.at(goal->trajectory.joint_names.at(i))->getCountsPerRotation()); + } + const double VELOCITY_MAX = abs(*std::max_element( - currTargetPosition.velocities.begin(), - currTargetPosition.velocities.end(), + velocityCopies.begin(), + velocityCopies.end(), [](double lhs, double rhs) -> bool { return abs(lhs) < abs(rhs); })); for (uint32_t i = 0; i < goal->trajectory.joint_names.size(); ++i) { auto jointVelocity{JOINT_SAFETY_HOLD_SPEED}; if (VELOCITY_MAX != 0) - jointVelocity = currTargetPosition.velocities.at(i) / VELOCITY_MAX * JOINT_SAFETY_MAX_SPEED; + jointVelocity = velocityCopies.at(i) / VELOCITY_MAX * JOINT_SAFETY_MAX_SPEED; - namedJointMap.at(goal->trajectory.joint_names.at(i))->setTarget(currTargetPosition.positions.at(i), jointVelocity); + namedJointMap.at(goal->trajectory.joint_names.at(i))->setTarget(velocityCopies.at(i), jointVelocity); } } @@ -214,36 +223,41 @@ auto main(int argc, char **argv) -> int { motors.push_back(wristLeftMotor); motors.push_back(wristRightMotor); - const auto turntablePositionMonitor{std::make_shared( - "aux0"s, - RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "turntable"), - n)}; - const auto shoulderPositionMonitor{std::make_shared( - "aux0"s, - RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "shoulder"), - n)}; - const auto elbowPositionMonitor{std::make_shared( - "aux1"s, - RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "elbow"), - n)}; - const auto forearmRollPositionMonitor{std::make_shared( - "aux1"s, - RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "forearmRoll"), - n)}; - const auto wristPitchPositionMonitor{std::make_shared( - "aux2"s, - RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "wristPitch"), - n)}; - const auto wristRollPositionMonitor{std::make_shared( - "aux2"s, - RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "wristRoll"), - n)}; + namedPositionMonitors.insert({"turntable_joint", std::make_shared( + "aux0"s, + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "turntable"), + n)}); + + namedPositionMonitors.insert({"shoulder_joint", std::make_shared( + "aux0"s, + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "shoulder"), + n)}); + + namedPositionMonitors.insert({"elbowPitch_joint", std::make_shared( + "aux1"s, + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "elbow"), + n)}); + + namedPositionMonitors.insert({"elbowRoll_joint", std::make_shared( + "aux1"s, + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "forearmRoll"), + n)}); + + namedPositionMonitors.insert({"wristPitch_joint", std::make_shared( + "aux2"s, + RoboclawChannel::A, + getEncoderConfigFromParams(encParams, "wristPitch"), + n)}); + + namedPositionMonitors.insert({"wristRoll_link", std::make_shared( + "aux2"s, + RoboclawChannel::B, + getEncoderConfigFromParams(encParams, "wristRoll"), + n)}); const auto turntableSpeedConverter{std::make_shared(turntableMotor, MotorSpeedDirection::REVERSE)}; const auto shoulderSpeedConverter{std::make_shared(shoulderMotor, MotorSpeedDirection::REVERSE)}; @@ -257,32 +271,32 @@ auto main(int argc, char **argv) -> int { namedJointMap.insert({"turntable_joint", std::make_unique( "turntable"s, - [turntablePositionMonitor]() -> double { return (*turntablePositionMonitor)(); }, + [turntablePositionMonitor=namedPositionMonitors.at("turntable_joint")]() -> double { return (*turntablePositionMonitor)(); }, [turntableSpeedConverter](double speed) { (*turntableSpeedConverter)(speed); }, n)}); namedJointMap.insert({"shoulder_joint", std::make_unique( "shoulder", - [shoulderPositionMonitor]() -> double { return (*shoulderPositionMonitor)(); }, + [shoulderPositionMonitor=namedPositionMonitors.at("shoulder_joint")]() -> double { return (*shoulderPositionMonitor)(); }, [shoulderSpeedConverter](double speed) { (*shoulderSpeedConverter)(speed); }, n)}); namedJointMap.insert({"elbowPitch_joint", std::make_unique( "elbow", - [elbowPositionMonitor]() -> double { return (*elbowPositionMonitor)(); }, + [elbowPositionMonitor=namedPositionMonitors.at("elbowPitch_joint")]() -> double { return (*elbowPositionMonitor)(); }, [elbowSpeedConverter](double speed) { (*elbowSpeedConverter)(speed); }, n)}); namedJointMap.insert({"elbowRoll_joint", std::make_unique( "forearmRoll", - [forearmRollPositionMonitor]() -> double { return (*forearmRollPositionMonitor)(); }, + [forearmRollPositionMonitor=namedPositionMonitors.at("elbowRoll_joint")]() -> double { return (*forearmRollPositionMonitor)(); }, [forearmRollSpeedConverter](double speed) { (*forearmRollSpeedConverter)(speed); }, n)}); namedJointMap.insert({"wristPitch_joint", std::make_unique( "wristPitch", - [wristPitchPositionMonitor]() -> double { return (*wristPitchPositionMonitor)(); }, + [wristPitchPositionMonitor=namedPositionMonitors.at("wristPitch_joint")]() -> double { return (*wristPitchPositionMonitor)(); }, [converter = differentialSpeedConverter](double speed) { converter->setPitchSpeed(speed); }, n)}); namedJointMap.insert({"wristRoll_link", std::make_unique( "wristRoll", - [wristRollPositionMonitor]() -> double { return (*wristRollPositionMonitor)(); }, + [wristRollPositionMonitor=namedPositionMonitors.at("wristRoll_link")]() -> double { return (*wristRollPositionMonitor)(); }, [converter = differentialSpeedConverter](double speed) { converter->setRollSpeed(speed); }, n)}); diff --git a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp index 9c179dc8..e0fe539c 100644 --- a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp +++ b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp @@ -2,6 +2,7 @@ #include "MathUtil.hpp" #include "RoboclawChannel.hpp" #include "ros/node_handle.h" +#include using std::literals::string_literals::operator""s; using MathUtil::RADIANS_PER_ROTATION; @@ -44,3 +45,7 @@ void SingleEncoderJointPositionMonitor::onEncoderReceived(const std_msgs::UInt32 auto rotations = MathUtil::corrMod(enc - offset, countsPerRotation) / countsPerRotation; position = MathUtil::corrMod(rotations * RADIANS_PER_ROTATION + M_PI, RADIANS_PER_ROTATION) - M_PI; } + +auto SingleEncoderJointPositionMonitor::getCountsPerRotation() const -> int32_t { + return this->countsPerRotation; +} diff --git a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp index cdf9938e..3f94d4e5 100644 --- a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp +++ b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp @@ -24,6 +24,8 @@ class SingleEncoderJointPositionMonitor { auto operator=(SingleEncoderJointPositionMonitor &&) -> SingleEncoderJointPositionMonitor & = delete; ~SingleEncoderJointPositionMonitor() = default; + [[nodiscard]] auto getCountsPerRotation() const -> int32_t; + private: void onEncoderReceived(const std_msgs::UInt32::ConstPtr &msg); From dcd1a6fb409fe375ee8986e8b758e62f48c3f392 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 20 Mar 2023 18:03:24 -0500 Subject: [PATCH 24/33] Fixed joint target setting code as requested in PR --- src/wr_control_drive_arm/src/ArmControlActionServer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 41769b72..dd868aab 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -129,7 +129,7 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, if (VELOCITY_MAX != 0) jointVelocity = velocityCopies.at(i) / VELOCITY_MAX * JOINT_SAFETY_MAX_SPEED; - namedJointMap.at(goal->trajectory.joint_names.at(i))->setTarget(velocityCopies.at(i), jointVelocity); + namedJointMap.at(goal->trajectory.joint_names.at(i))->setTarget(currTargetPosition.positions.at(i), jointVelocity); } } From 1b774df978038d97330062a41263d1d39b8303cd Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 20 Mar 2023 19:15:06 -0500 Subject: [PATCH 25/33] Restructured arm parameter files, added gear ratios to motor speed converters --- .../config/arm_parameters_mock.yaml | 35 ++++++++++++++++++ .../config/arm_parameters_real.yaml | 37 +++++++++++++++++++ .../config/encoder_parameters_mock.yaml | 19 ---------- .../config/encoder_parameters_real.yaml | 19 ---------- .../src/DirectJointToMotorSpeedConverter.cpp | 9 ++++- .../src/DirectJointToMotorSpeedConverter.hpp | 9 ++++- 6 files changed, 87 insertions(+), 41 deletions(-) create mode 100644 src/wr_control_drive_arm/config/arm_parameters_mock.yaml create mode 100644 src/wr_control_drive_arm/config/arm_parameters_real.yaml delete mode 100644 src/wr_control_drive_arm/config/encoder_parameters_mock.yaml delete mode 100644 src/wr_control_drive_arm/config/encoder_parameters_real.yaml diff --git a/src/wr_control_drive_arm/config/arm_parameters_mock.yaml b/src/wr_control_drive_arm/config/arm_parameters_mock.yaml new file mode 100644 index 00000000..9ae93fc5 --- /dev/null +++ b/src/wr_control_drive_arm/config/arm_parameters_mock.yaml @@ -0,0 +1,35 @@ +arm_parameters: + elbow: + encoder_parameters: + counts_per_rotation: 1000 + offset: 500 + motor_parameters: + gear_ratio: 0 #placeholder + forearmRoll: + encoder_parameters: + counts_per_rotation: 1000 + offset: 500 + motor_parameters: + gear_ratio: 0 #placeholder + shoulder: + encoder_parameters: + counts_per_rotation: 1000 + offset: 500 + motor_parameters: + gear_ratio: 0 #placeholder + turntable: + encoder_parameters: + counts_per_rotation: 1000 + offset: 500 + wristPitch: + encoder_parameters: + counts_per_rotation: 1000 + offset: 500 + motor_parameters: + gear_ratio: 0 #placeholder + wristRoll: + encoder_parameters: + counts_per_rotation: 1000 + offset: 500 + motor_parameters: + gear_ratio: 0 #placeholder diff --git a/src/wr_control_drive_arm/config/arm_parameters_real.yaml b/src/wr_control_drive_arm/config/arm_parameters_real.yaml new file mode 100644 index 00000000..360505f8 --- /dev/null +++ b/src/wr_control_drive_arm/config/arm_parameters_real.yaml @@ -0,0 +1,37 @@ +arm_parameters: + elbow: + encoder_parameters: + counts_per_rotation: 1850 + offset: 546 + motor_parameters: + gear_ratio: 0 #placeholder + forearmRoll: + encoder_parameters: + counts_per_rotation: -1850 + offset: 576 + motor_parameters: + gear_ratio: 0 #placeholder + shoulder: + encoder_parameters: + counts_per_rotation: 5550 + offset: 1281 + motor_parameters: + gear_ratio: 0 #placeholder + turntable: + encoder_parameters: + counts_per_rotation: 6900 #7200 + offset: 90 + motor_parameters: + gear_ratio: 0 #placeholder + wristPitch: + encoder_parameters: + counts_per_rotation: -1850 + offset: 886 + motor_parameters: + gear_ratio: 0 #placeholder + wristRoll: + encoder_parameters: + counts_per_rotation: -1850 + offset: 981 + motor_parameters: + gear_ratio: 0 #placeholder diff --git a/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml b/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml deleted file mode 100644 index 91e14a26..00000000 --- a/src/wr_control_drive_arm/config/encoder_parameters_mock.yaml +++ /dev/null @@ -1,19 +0,0 @@ -encoder_parameters: - elbow: - counts_per_rotation: 1000 - offset: 500 - forearmRoll: - counts_per_rotation: 1000 - offset: 500 - shoulder: - counts_per_rotation: 1000 - offset: 500 - turntable: - counts_per_rotation: 1000 - offset: 500 - wristPitch: - counts_per_rotation: 1000 - offset: 500 - wristRoll: - counts_per_rotation: 1000 - offset: 500 diff --git a/src/wr_control_drive_arm/config/encoder_parameters_real.yaml b/src/wr_control_drive_arm/config/encoder_parameters_real.yaml deleted file mode 100644 index b4d31f7c..00000000 --- a/src/wr_control_drive_arm/config/encoder_parameters_real.yaml +++ /dev/null @@ -1,19 +0,0 @@ -encoder_parameters: - elbow: - counts_per_rotation: 1850 - offset: 546 - forearmRoll: - counts_per_rotation: -1850 - offset: 576 - shoulder: - counts_per_rotation: 5550 - offset: 1281 - turntable: - counts_per_rotation: 6900 #7200 - offset: 90 - wristPitch: - counts_per_rotation: -1850 - offset: 886 - wristRoll: - counts_per_rotation: -1850 - offset: 981 diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp index 67fd0568..ce792dd2 100644 --- a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp @@ -1,8 +1,9 @@ #include "DirectJointToMotorSpeedConverter.hpp" -DirectJointToMotorSpeedConverter::DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction) +DirectJointToMotorSpeedConverter::DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction, MotorConfiguration config) : outputMotor{std::move(outputMotor)}, - direction{direction} {} + direction{direction}, + gearRatio{config.gearRatio} {} void DirectJointToMotorSpeedConverter::operator()(double speed) { double actualSpeed{0}; // In event of enum error, stop the motor @@ -16,3 +17,7 @@ void DirectJointToMotorSpeedConverter::operator()(double speed) { } outputMotor->setSpeed(actualSpeed); } + +auto DirectJointToMotorSpeedConverter::getGearRatio() const -> double { + return this->gearRatio; +} diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp index 6a117435..3b6a1de8 100644 --- a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp @@ -9,9 +9,13 @@ enum class MotorSpeedDirection { REVERSE }; +struct MotorConfiguration { + double gearRatio; +}; + class DirectJointToMotorSpeedConverter { public: - DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction); + DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction, MotorConfiguration config); void operator()(double speed); DirectJointToMotorSpeedConverter(const DirectJointToMotorSpeedConverter &) = default; @@ -20,9 +24,12 @@ class DirectJointToMotorSpeedConverter { auto operator=(DirectJointToMotorSpeedConverter &&) -> DirectJointToMotorSpeedConverter & = delete; ~DirectJointToMotorSpeedConverter() = default; + [[nodiscard]] auto getGearRatio() const -> double; + private: const MotorSpeedDirection direction; const std::shared_ptr outputMotor; + const double gearRatio; }; #endif \ No newline at end of file From e895166c7f1ccfd991484a9a850fa8498016e7c8 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 20 Mar 2023 19:29:09 -0500 Subject: [PATCH 26/33] Removed gear ratios from direct motor speed controllers, they are not meant to go there --- .../src/DirectJointToMotorSpeedConverter.cpp | 9 ++------- .../src/DirectJointToMotorSpeedConverter.hpp | 9 +-------- 2 files changed, 3 insertions(+), 15 deletions(-) diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp index ce792dd2..67fd0568 100644 --- a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.cpp @@ -1,9 +1,8 @@ #include "DirectJointToMotorSpeedConverter.hpp" -DirectJointToMotorSpeedConverter::DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction, MotorConfiguration config) +DirectJointToMotorSpeedConverter::DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction) : outputMotor{std::move(outputMotor)}, - direction{direction}, - gearRatio{config.gearRatio} {} + direction{direction} {} void DirectJointToMotorSpeedConverter::operator()(double speed) { double actualSpeed{0}; // In event of enum error, stop the motor @@ -17,7 +16,3 @@ void DirectJointToMotorSpeedConverter::operator()(double speed) { } outputMotor->setSpeed(actualSpeed); } - -auto DirectJointToMotorSpeedConverter::getGearRatio() const -> double { - return this->gearRatio; -} diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp index 3b6a1de8..6a117435 100644 --- a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp @@ -9,13 +9,9 @@ enum class MotorSpeedDirection { REVERSE }; -struct MotorConfiguration { - double gearRatio; -}; - class DirectJointToMotorSpeedConverter { public: - DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction, MotorConfiguration config); + DirectJointToMotorSpeedConverter(std::shared_ptr outputMotor, MotorSpeedDirection direction); void operator()(double speed); DirectJointToMotorSpeedConverter(const DirectJointToMotorSpeedConverter &) = default; @@ -24,12 +20,9 @@ class DirectJointToMotorSpeedConverter { auto operator=(DirectJointToMotorSpeedConverter &&) -> DirectJointToMotorSpeedConverter & = delete; ~DirectJointToMotorSpeedConverter() = default; - [[nodiscard]] auto getGearRatio() const -> double; - private: const MotorSpeedDirection direction; const std::shared_ptr outputMotor; - const double gearRatio; }; #endif \ No newline at end of file From 1114303954556cb22cbd71c8e134f9849efc00ed Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Wed, 22 Mar 2023 18:37:25 -0500 Subject: [PATCH 27/33] Added gear ratios to joint position monitors, changed action server and joint state publisher to pull correct values from arm params --- .../src/ArmControlActionServer.cpp | 38 ++++++++++++------- .../src/JointStatePublisher.cpp | 30 ++++++++++----- .../src/SingleEncoderJointPositionMonitor.cpp | 14 +++++-- .../src/SingleEncoderJointPositionMonitor.hpp | 8 +++- 4 files changed, 62 insertions(+), 28 deletions(-) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index dd868aab..93a24386 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -161,8 +161,12 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, } auto getEncoderConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> EncoderConfiguration { - return {.countsPerRotation = static_cast(params[jointName]["counts_per_rotation"]), - .offset = static_cast(params[jointName]["offset"])}; + return {.countsPerRotation = static_cast(params[jointName]["encoder_parameters"]["counts_per_rotation"]), + .offset = static_cast(params[jointName]["encoder_parameters"]["offset"])}; +} + +auto getMotorConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> MotorConfiguration { + return {.gearRatio = static_cast(params[jointName]["motor_configurations"]["gear_ratio"])}; } void checkOverCurrentFaults(const std::vector> &motors){ @@ -195,8 +199,8 @@ auto main(int argc, char **argv) -> int { ros::NodeHandle n; ros::NodeHandle pn{"~"}; - XmlRpcValue encParams; - pn.getParam("encoder_parameters", encParams); + XmlRpcValue armParams; + pn.getParam("arm_parameters", armParams); // Initialize all motors with their MoveIt name, WRoboclaw initialization, // and reference to the current node @@ -226,43 +230,49 @@ auto main(int argc, char **argv) -> int { namedPositionMonitors.insert({"turntable_joint", std::make_shared( "aux0"s, RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "turntable"), + getEncoderConfigFromParams(armParams, "turntable"), + getMotorConfigFromParams(armParams, "turntable"), n)}); namedPositionMonitors.insert({"shoulder_joint", std::make_shared( "aux0"s, RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "shoulder"), + getEncoderConfigFromParams(armParams, "shoulder"), + getMotorConfigFromParams(armParams, "shoulder"), n)}); namedPositionMonitors.insert({"elbowPitch_joint", std::make_shared( "aux1"s, RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "elbow"), + getEncoderConfigFromParams(armParams, "elbow"), + getMotorConfigFromParams(armParams, "elbow"), n)}); namedPositionMonitors.insert({"elbowRoll_joint", std::make_shared( "aux1"s, RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "forearmRoll"), + getEncoderConfigFromParams(armParams, "forearmRoll"), + getMotorConfigFromParams(armParams, "forearmRoll"), n)}); namedPositionMonitors.insert({"wristPitch_joint", std::make_shared( "aux2"s, RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "wristPitch"), + getEncoderConfigFromParams(armParams, "wristPitch"), + getMotorConfigFromParams(armParams, "wristPitch"), n)}); namedPositionMonitors.insert({"wristRoll_link", std::make_shared( "aux2"s, RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "wristRoll"), + getEncoderConfigFromParams(armParams, "wristRoll"), + getMotorConfigFromParams(armParams, "wristRoll"), n)}); - const auto turntableSpeedConverter{std::make_shared(turntableMotor, MotorSpeedDirection::REVERSE)}; - const auto shoulderSpeedConverter{std::make_shared(shoulderMotor, MotorSpeedDirection::REVERSE)}; - const auto elbowSpeedConverter{std::make_shared(elbowMotor, MotorSpeedDirection::REVERSE)}; - const auto forearmRollSpeedConverter{std::make_shared(forearmRollMotor, MotorSpeedDirection::REVERSE)}; + const auto turntableSpeedConverter{std::make_shared(turntableMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "turntable"))}; + const auto shoulderSpeedConverter{std::make_shared(shoulderMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "shoulder"))}; + const auto elbowSpeedConverter{std::make_shared(elbowMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "elbow"))}; + const auto forearmRollSpeedConverter{std::make_shared(forearmRollMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "forearmRoll"))}; const auto differentialSpeedConverter{std::make_shared(wristLeftMotor, wristRightMotor)}; // Initialize all Joints diff --git a/src/wr_control_drive_arm/src/JointStatePublisher.cpp b/src/wr_control_drive_arm/src/JointStatePublisher.cpp index 3a93cba6..3a602563 100644 --- a/src/wr_control_drive_arm/src/JointStatePublisher.cpp +++ b/src/wr_control_drive_arm/src/JointStatePublisher.cpp @@ -58,8 +58,12 @@ void publishJointStates(const ros::TimerEvent &event) { } auto getEncoderConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> EncoderConfiguration { - return {.countsPerRotation = static_cast(params[jointName]["counts_per_rotation"]), - .offset = static_cast(params[jointName]["offset"])}; + return {.countsPerRotation = static_cast(params[jointName]["encoder_parameters"]["counts_per_rotation"]), + .offset = static_cast(params[jointName]["encoder_parameters"]["offset"])}; +} + +auto getMotorConfigFromParams(const XmlRpcValue ¶ms, const std::string &jointName) -> MotorConfiguration { + return {.gearRatio = static_cast(params[jointName]["motor_configurations"]["gear_ratio"])}; } /** @@ -78,43 +82,49 @@ auto main(int argc, char **argv) -> int { ros::NodeHandle n; ros::NodeHandle pn{"~"}; - XmlRpcValue encParams; - pn.getParam("encoder_parameters", encParams); + XmlRpcValue armParams; + pn.getParam("arm_parameters", armParams); namedJointPositionMonitors.try_emplace("elbowPitch_joint", "aux1", RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "elbow"), + getEncoderConfigFromParams(armParams, "elbow"), + getMotorConfigFromParams(armParams, "elbow"), n); namedJointPositionMonitors.try_emplace("elbowRoll_joint", "aux1", RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "forearmRoll"), + getEncoderConfigFromParams(armParams, "forearmRoll"), + getMotorConfigFromParams(armParams, "forearmRoll"), n); namedJointPositionMonitors.try_emplace("shoulder_joint", "aux0", RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "shoulder"), + getEncoderConfigFromParams(armParams, "shoulder"), + getMotorConfigFromParams(armParams, "shoulder"), n); namedJointPositionMonitors.try_emplace("turntable_joint", "aux0", RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "turntable"), + getEncoderConfigFromParams(armParams, "turntable"), + getMotorConfigFromParams(armParams, "turntable"), n); namedJointPositionMonitors.try_emplace("wristPitch_joint", "aux2", RoboclawChannel::A, - getEncoderConfigFromParams(encParams, "wristPitch"), + getEncoderConfigFromParams(armParams, "wristPitch"), + getMotorConfigFromParams(armParams, "wristPitch"), n); namedJointPositionMonitors.try_emplace("wristRoll_link", "aux2", RoboclawChannel::B, - getEncoderConfigFromParams(encParams, "wristRoll"), + getEncoderConfigFromParams(armParams, "wristRoll"), + getMotorConfigFromParams(armParams, "wristRoll"), n); // Initialize the Joint State Data Publisher diff --git a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp index e0fe539c..d657f1c8 100644 --- a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp +++ b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.cpp @@ -10,10 +10,12 @@ using MathUtil::RADIANS_PER_ROTATION; SingleEncoderJointPositionMonitor::SingleEncoderJointPositionMonitor( const std::string &controllerName, RoboclawChannel channel, - EncoderConfiguration config, + EncoderConfiguration eConfig, + MotorConfiguration mConfig, ros::NodeHandle node) - : countsPerRotation{config.countsPerRotation}, - offset{config.offset}, + : countsPerRotation{eConfig.countsPerRotation}, + offset{eConfig.offset}, + gearRatio{mConfig.gearRatio}, position{0}, encoderSubscriber{ std::make_shared(node.subscribe( @@ -26,6 +28,7 @@ SingleEncoderJointPositionMonitor::SingleEncoderJointPositionMonitor( const SingleEncoderJointPositionMonitor &other) : countsPerRotation(other.countsPerRotation), offset(other.offset), + gearRatio{other.getGearRatio()}, encoderSubscriber{other.encoderSubscriber}, position{other.position.load()} {} @@ -33,6 +36,7 @@ SingleEncoderJointPositionMonitor::SingleEncoderJointPositionMonitor( SingleEncoderJointPositionMonitor &&other) noexcept : countsPerRotation(other.countsPerRotation), offset(other.offset), + gearRatio(other.getGearRatio()), encoderSubscriber{std::move(other.encoderSubscriber)}, position{other.position.load()} {} @@ -49,3 +53,7 @@ void SingleEncoderJointPositionMonitor::onEncoderReceived(const std_msgs::UInt32 auto SingleEncoderJointPositionMonitor::getCountsPerRotation() const -> int32_t { return this->countsPerRotation; } + +auto SingleEncoderJointPositionMonitor::getGearRatio() const -> double { + return this->gearRatio; +} \ No newline at end of file diff --git a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp index 3f94d4e5..e57437b1 100644 --- a/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp +++ b/src/wr_control_drive_arm/src/SingleEncoderJointPositionMonitor.hpp @@ -13,9 +13,13 @@ struct EncoderConfiguration { int32_t offset; }; +struct MotorConfiguration { + double gearRatio; +}; + class SingleEncoderJointPositionMonitor { public: - SingleEncoderJointPositionMonitor(const std::string &controllerName, RoboclawChannel channel, EncoderConfiguration config, ros::NodeHandle node); + SingleEncoderJointPositionMonitor(const std::string &controllerName, RoboclawChannel channel, EncoderConfiguration eConfig, MotorConfiguration mConfig, ros::NodeHandle node); auto operator()() -> double; SingleEncoderJointPositionMonitor(const SingleEncoderJointPositionMonitor &); @@ -25,6 +29,7 @@ class SingleEncoderJointPositionMonitor { ~SingleEncoderJointPositionMonitor() = default; [[nodiscard]] auto getCountsPerRotation() const -> int32_t; + [[nodiscard]] auto getGearRatio() const -> double; private: void onEncoderReceived(const std_msgs::UInt32::ConstPtr &msg); @@ -33,6 +38,7 @@ class SingleEncoderJointPositionMonitor { std::shared_ptr encoderSubscriber; const int32_t countsPerRotation; const int32_t offset; + const double gearRatio; }; #endif \ No newline at end of file From 38992951f2332a69c6687c596be128e37e513747 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 3 Apr 2023 18:46:05 -0500 Subject: [PATCH 28/33] Updated launch files to reference correct parameters, added gear ratios to parameter files --- .../config/arm_parameters_mock.yaml | 12 +++++++----- .../config/arm_parameters_real.yaml | 12 ++++++------ src/wr_control_drive_arm/launch/actionserver.launch | 4 ++-- .../launch/jointstatepublisher.launch | 4 ++-- 4 files changed, 17 insertions(+), 15 deletions(-) diff --git a/src/wr_control_drive_arm/config/arm_parameters_mock.yaml b/src/wr_control_drive_arm/config/arm_parameters_mock.yaml index 9ae93fc5..51dc5ffb 100644 --- a/src/wr_control_drive_arm/config/arm_parameters_mock.yaml +++ b/src/wr_control_drive_arm/config/arm_parameters_mock.yaml @@ -4,32 +4,34 @@ arm_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 3 forearmRoll: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 3 shoulder: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 9 turntable: encoder_parameters: counts_per_rotation: 1000 offset: 500 + motor_parameters: + gear_ratio: 3 wristPitch: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 2 wristRoll: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 2 diff --git a/src/wr_control_drive_arm/config/arm_parameters_real.yaml b/src/wr_control_drive_arm/config/arm_parameters_real.yaml index 360505f8..b9f61720 100644 --- a/src/wr_control_drive_arm/config/arm_parameters_real.yaml +++ b/src/wr_control_drive_arm/config/arm_parameters_real.yaml @@ -4,34 +4,34 @@ arm_parameters: counts_per_rotation: 1850 offset: 546 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 3 forearmRoll: encoder_parameters: counts_per_rotation: -1850 offset: 576 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 3 shoulder: encoder_parameters: counts_per_rotation: 5550 offset: 1281 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 9 turntable: encoder_parameters: counts_per_rotation: 6900 #7200 offset: 90 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 3 wristPitch: encoder_parameters: counts_per_rotation: -1850 offset: 886 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 2 wristRoll: encoder_parameters: counts_per_rotation: -1850 offset: 981 motor_parameters: - gear_ratio: 0 #placeholder + gear_ratio: 2 diff --git a/src/wr_control_drive_arm/launch/actionserver.launch b/src/wr_control_drive_arm/launch/actionserver.launch index 4bf4ebe7..a1c5c9e0 100644 --- a/src/wr_control_drive_arm/launch/actionserver.launch +++ b/src/wr_control_drive_arm/launch/actionserver.launch @@ -8,12 +8,12 @@ type="ArmControlActionServer" output="screen"> diff --git a/src/wr_control_drive_arm/launch/jointstatepublisher.launch b/src/wr_control_drive_arm/launch/jointstatepublisher.launch index 8aa7f82c..9b662856 100644 --- a/src/wr_control_drive_arm/launch/jointstatepublisher.launch +++ b/src/wr_control_drive_arm/launch/jointstatepublisher.launch @@ -3,9 +3,9 @@ - - From 99886160ad1e0c93e274a6468c8716a09dd9b1a8 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 3 Apr 2023 19:28:36 -0500 Subject: [PATCH 29/33] Updated roboclaw offsets, cleaned up velocity scaling in arm control --- .../src/ArmControlActionServer.cpp | 16 +++++++++++++++- src/wr_hsi_roboclaw/config/roboclaw_enc.yaml | 8 ++++++++ 2 files changed, 23 insertions(+), 1 deletion(-) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 93a24386..0b18e536 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -113,22 +113,36 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, return; } + // Copy of the velocities received from MoveIt std::vector velocityCopies{currTargetPosition.velocities}; for (uint32_t i = 0; i < goal->trajectory.joint_names.size(); ++i) { - velocityCopies.at(i) *= abs(namedPositionMonitors.at(goal->trajectory.joint_names.at(i))->getCountsPerRotation()); + + // The joint that is currently being scaled + auto currJoint = goal->trajectory.joint_names.at(i); + + // The position monitor whose velocity is currently being scaled + auto currPosMtr = namedPositionMonitors.at(currJoint); + + // Scale by counts per rotation and gear ratio + velocityCopies.at(i) *= abs(currPosMtr->getCountsPerRotation()*currPosMtr->getGearRatio()); } + // Get the maximum velocity assigned to any joint const double VELOCITY_MAX = abs(*std::max_element( velocityCopies.begin(), velocityCopies.end(), [](double lhs, double rhs) -> bool { return abs(lhs) < abs(rhs); })); for (uint32_t i = 0; i < goal->trajectory.joint_names.size(); ++i) { + // Set joint to hold speed in case the greatest velocity comes through as 0 auto jointVelocity{JOINT_SAFETY_HOLD_SPEED}; + + // Scale all velocities by the safety max speed with respect to the maximum velocity given by MoveIt if (VELOCITY_MAX != 0) jointVelocity = velocityCopies.at(i) / VELOCITY_MAX * JOINT_SAFETY_MAX_SPEED; + // Set the joint's velocity namedJointMap.at(goal->trajectory.joint_names.at(i))->setTarget(currTargetPosition.positions.at(i), jointVelocity); } } diff --git a/src/wr_hsi_roboclaw/config/roboclaw_enc.yaml b/src/wr_hsi_roboclaw/config/roboclaw_enc.yaml index c263a2c6..03b11c22 100644 --- a/src/wr_hsi_roboclaw/config/roboclaw_enc.yaml +++ b/src/wr_hsi_roboclaw/config/roboclaw_enc.yaml @@ -7,36 +7,44 @@ claws: enc_left: enabled: true max_speed: 100 # TODO probably don't actually need all these encoders + offset: 500 enc_right: enabled: true max_speed: 100 + offset: 500 aux1: # arm elbow/forearm, science ? topic: '/hsi/roboclaw/aux1' address: 0x81 enc_left: enabled: true max_speed: 100 + offset: 500 enc_right: enabled: true max_speed: 100 + offset: 500 aux2: # arm wrist, science ? topic: '/hsi/roboclaw/aux2' address: 0x82 enc_left: enabled: true max_speed: 100 + offset: 500 enc_right: enabled: true max_speed: 100 + offset: 500 aux3: # arm manip, science ? topic: '/hsi/roboclaw/aux3' address: 0x83 enc_left: enabled: true max_speed: 100 + offset: 500 enc_right: enabled: true max_speed: 100 + offset: 500 drive: # drive train topic: '/hsi/roboclaw/drive' address: 0x84 From 62f6e63f37b9cf7a70815806f588e757a62fb270 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 10 Apr 2023 18:08:35 -0500 Subject: [PATCH 30/33] Added map to store position monitor references --- src/wr_control_drive_arm/src/ArmControlActionServer.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 0b18e536..a6cbf4bb 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -58,12 +58,16 @@ constexpr float TIMER_CALLBACK_DURATION{1.0 / 50.0}; */ std::unordered_map> namedJointMap; +/** + * @brief Defines space for all joint position monitor references + */ std::unordered_map> namedPositionMonitors; /** * @brief Simplify the SimpleActionServer reference name */ using Server = actionlib::SimpleActionServer; + /** * @brief The service server for enabling IK */ From a84b80c0e965e5056ea383f0dbfad2f36aba9ad6 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 10 Apr 2023 18:49:10 -0500 Subject: [PATCH 31/33] fixed error in constructor --- src/wr_control_drive_arm/src/ArmControlActionServer.cpp | 8 ++++---- .../src/DirectJointToMotorSpeedConverter.hpp | 1 + 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index a6cbf4bb..685ed202 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -287,10 +287,10 @@ auto main(int argc, char **argv) -> int { getMotorConfigFromParams(armParams, "wristRoll"), n)}); - const auto turntableSpeedConverter{std::make_shared(turntableMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "turntable"))}; - const auto shoulderSpeedConverter{std::make_shared(shoulderMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "shoulder"))}; - const auto elbowSpeedConverter{std::make_shared(elbowMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "elbow"))}; - const auto forearmRollSpeedConverter{std::make_shared(forearmRollMotor, MotorSpeedDirection::REVERSE, getMotorConfigFromParams(armParams, "forearmRoll"))}; + const auto turntableSpeedConverter{std::make_shared(turntableMotor, MotorSpeedDirection::REVERSE)}; + const auto shoulderSpeedConverter{std::make_shared(shoulderMotor, MotorSpeedDirection::REVERSE)}; + const auto elbowSpeedConverter{std::make_shared(elbowMotor, MotorSpeedDirection::REVERSE)}; + const auto forearmRollSpeedConverter{std::make_shared(forearmRollMotor, MotorSpeedDirection::REVERSE)}; const auto differentialSpeedConverter{std::make_shared(wristLeftMotor, wristRightMotor)}; // Initialize all Joints diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp index 6a117435..f32ce157 100644 --- a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp @@ -2,6 +2,7 @@ #define DIRECT_JOINT_TO_MOTOR_SPEED_CONVERTER_H #include "Motor.hpp" +#include "SingleEncoderJointPositionMonitor.hpp" #include enum class MotorSpeedDirection { From 875b3261855358b6caaae00fa4b0de3a9bfd2005 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Wed, 12 Apr 2023 19:22:06 -0500 Subject: [PATCH 32/33] Tuned gear ratios --- src/wr_control_drive_arm/config/arm_parameters_real.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/wr_control_drive_arm/config/arm_parameters_real.yaml b/src/wr_control_drive_arm/config/arm_parameters_real.yaml index b9f61720..511c0c23 100644 --- a/src/wr_control_drive_arm/config/arm_parameters_real.yaml +++ b/src/wr_control_drive_arm/config/arm_parameters_real.yaml @@ -28,10 +28,10 @@ arm_parameters: counts_per_rotation: -1850 offset: 886 motor_parameters: - gear_ratio: 2 + gear_ratio: 4.875 wristRoll: encoder_parameters: counts_per_rotation: -1850 offset: 981 motor_parameters: - gear_ratio: 2 + gear_ratio: 4.875 From ff167a65d4136add9f5545a9132999e217d4a384 Mon Sep 17 00:00:00 2001 From: Jack Zautner Date: Mon, 24 Apr 2023 18:00:58 -0500 Subject: [PATCH 33/33] Updated code in compliance with #41 --- .../config/arm_parameters_mock.yaml | 12 ++++++------ .../src/ArmControlActionServer.cpp | 4 ++-- .../src/DirectJointToMotorSpeedConverter.hpp | 1 - 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/src/wr_control_drive_arm/config/arm_parameters_mock.yaml b/src/wr_control_drive_arm/config/arm_parameters_mock.yaml index 51dc5ffb..a8b1e10d 100644 --- a/src/wr_control_drive_arm/config/arm_parameters_mock.yaml +++ b/src/wr_control_drive_arm/config/arm_parameters_mock.yaml @@ -4,34 +4,34 @@ arm_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 3 + gear_ratio: 1 forearmRoll: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 3 + gear_ratio: 1 shoulder: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 9 + gear_ratio: 1 turntable: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 3 + gear_ratio: 1 wristPitch: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 2 + gear_ratio: 1 wristRoll: encoder_parameters: counts_per_rotation: 1000 offset: 500 motor_parameters: - gear_ratio: 2 + gear_ratio: 1 diff --git a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp index 685ed202..7b3f6ae9 100644 --- a/src/wr_control_drive_arm/src/ArmControlActionServer.cpp +++ b/src/wr_control_drive_arm/src/ArmControlActionServer.cpp @@ -126,10 +126,10 @@ void execute(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, auto currJoint = goal->trajectory.joint_names.at(i); // The position monitor whose velocity is currently being scaled - auto currPosMtr = namedPositionMonitors.at(currJoint); + auto& currPosMtr = *namedPositionMonitors.at(currJoint); // Scale by counts per rotation and gear ratio - velocityCopies.at(i) *= abs(currPosMtr->getCountsPerRotation()*currPosMtr->getGearRatio()); + velocityCopies.at(i) *= abs(currPosMtr.getCountsPerRotation()*currPosMtr.getGearRatio()); } // Get the maximum velocity assigned to any joint diff --git a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp index f32ce157..6a117435 100644 --- a/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp +++ b/src/wr_control_drive_arm/src/DirectJointToMotorSpeedConverter.hpp @@ -2,7 +2,6 @@ #define DIRECT_JOINT_TO_MOTOR_SPEED_CONVERTER_H #include "Motor.hpp" -#include "SingleEncoderJointPositionMonitor.hpp" #include enum class MotorSpeedDirection {