23 #ifndef _ARMARX_LIB_DSController_DSJointCarryController_H
24 #define _ARMARX_LIB_DSController_DSJointCarryController_H
26 #include <VirtualRobot/Robot.h>
27 #include <VirtualRobot/Tools/Gravity.h>
28 #include <VirtualRobot/IK/DifferentialIK.h>
37 #include <armarx/control/ds_controller/DSControllerInterface.h>
53 std::vector<double>
Mu_;
80 std::ifstream infile { fileName };
81 std::string objDefs = { std::istreambuf_iterator<char>(infile), std::istreambuf_iterator<char>() };
83 json->fromString(objDefs);
90 scaling = json->getDouble(
"Scaling");
91 v_max = json->getDouble(
"MaxVelocity");
95 std::cout <<
"line 162." << std::endl;
98 for (
int i = 0; i < 3; ++i)
103 std::cout <<
"Finished GMM." << std::endl;
109 const Eigen::Vector3f& positionInMeter,
110 float positionErrorToleranceInMeter)
113 position_error.Resize(3);
116 desired_vel.Resize(3);
118 Eigen::Vector3f positionError = positionInMeter -
guard_target;
119 if (positionError.norm() < positionErrorToleranceInMeter)
121 positionError.setZero();
124 for (
int i = 0; i < 3; ++i)
126 position_error(i) = positionError(i);
129 desired_vel =
guard_gmm->getVelocity(position_error);
137 if (std::isnan(lenVec))
197 return "DSJointCarryController";
206 void setGuardOrientation(
const Ice::FloatSeq& guardOrientationInRobotBase,
const Ice::Current&);
207 void setDesiredGuardOri(
const Ice::FloatSeq& desiredOrientationInRobotBase,
const Ice::Current&);
212 mutable MutexType interface2CtrlDataMutex;
214 float deadzone(
float currentValue,
float targetValue,
float threshold);
217 struct DSJointCarryControllerSensorData
221 Eigen::Vector3f left_force;
222 Eigen::Vector3f right_force;
228 struct DSCtrlDebugInfo
230 Eigen::Vector3f leftDesiredLinearVelocity;
231 Eigen::Vector3f rightDesiredLinearVelocity;
235 struct Interface2CtrlData
237 Eigen::Vector3f guardToHandInMeter;
240 Eigen::Vector3f guardRotationStiffness;
241 Eigen::Vector3f guardObsAvoidVel;
243 TripleBuffer<Interface2CtrlData> interface2CtrlData;
247 StringFloatDictionary desired_torques;
249 TripleBuffer<DSRTDebugInfo> debugDataInfo;
251 struct Ctrl2InterfaceData
255 TripleBuffer<Ctrl2InterfaceData> ctrl2InterfaceData;
257 std::vector<const SensorValue1DoFActuatorTorque*> left_torqueSensors;
258 std::vector<const SensorValue1DoFGravityTorque*> left_gravityTorqueSensors;
259 std::vector<const SensorValue1DoFActuatorVelocity*> left_velocitySensors;
260 std::vector<const SensorValue1DoFActuatorPosition*> left_positionSensors;
262 std::vector<const SensorValue1DoFActuatorTorque*> right_torqueSensors;
263 std::vector<const SensorValue1DoFGravityTorque*> right_gravityTorqueSensors;
264 std::vector<const SensorValue1DoFActuatorVelocity*> right_velocitySensors;
265 std::vector<const SensorValue1DoFActuatorPosition*> right_positionSensors;
267 const SensorValueForceTorque* leftForceTorque;
268 const SensorValueForceTorque* rightForceTorque;
270 std::vector<ControlTarget1DoFActuatorTorque*> left_torque_targets;
271 std::vector<ControlTarget1DoFActuatorTorque*> right_torque_targets;
273 VirtualRobot::RobotNodePtr left_arm_tcp;
274 VirtualRobot::RobotNodePtr right_arm_tcp;
276 VirtualRobot::RobotNodePtr left_sensor_frame;
277 VirtualRobot::RobotNodePtr right_sensor_frame;
279 VirtualRobot::DifferentialIKPtr left_ik;
280 VirtualRobot::DifferentialIKPtr right_ik;
285 Eigen::Vector3f left_currentTCPLinearVelocity_filtered;
286 Eigen::Vector3f left_currentTCPAngularVelocity_filtered;
287 Eigen::Vector3f right_currentTCPLinearVelocity_filtered;
288 Eigen::Vector3f right_currentTCPAngularVelocity_filtered;
290 Eigen::VectorXf left_jointVelocity_filtered;
291 Eigen::VectorXf right_jointVelocity_filtered;
293 Eigen::VectorXf left_desiredTorques_filtered;
294 Eigen::VectorXf right_desiredTorques_filtered;
295 Eigen::Vector3f left_tcpDesiredTorque_filtered;
296 Eigen::Vector3f right_tcpDesiredTorque_filtered;
298 float smooth_startup;
300 DSJointCarryControllerConfigPtr cfg;
301 float filterTimeConstant;
303 std::vector<std::string> left_jointNames;
304 std::vector<std::string> right_jointNames;
308 std::vector<float> Damping;
312 float null_torqueLimit;
314 float nullspaceDamping;
315 Eigen::VectorXf left_qnullspace;
316 Eigen::VectorXf right_qnullspace;
321 float positionErrorTolerance;
322 bool controllerStopRequested =
false;
323 bool controllerRunFinished =
false;