24#include <boost/algorithm/clamp.hpp>
25#include <boost/archive/text_iarchive.hpp>
26#include <boost/archive/text_oarchive.hpp>
28#include <SimoxUtility/math/compare/is_equal.h>
29#include <SimoxUtility/math/convert/mat4f_to_pos.h>
30#include <SimoxUtility/math/convert/mat4f_to_quat.h>
31#include <VirtualRobot/MathTools.h>
38 NJointControllerRegistration<KeypointMPController>
42 const NJointControllerConfigPtr& config,
45 ARMARX_INFO <<
"creating task-space admittance controller";
46 KeypointMPControllerConfigPtr cfg = KeypointMPControllerConfigPtr::dynamicCast(config);
52 kinematicChainName = cfg->nodeSetName;
54 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
58 for (
size_t i = 0; i < rns->getSize(); ++i)
60 std::string jointName = rns->getNode(i)->getName();
61 jointNames.push_back(jointName);
66 auto casted_ct = ct->
asA<ControlTarget1DoFActuatorTorque>();
68 targets.push_back(casted_ct);
70 const SensorValue1DoFActuatorTorque* torqueSensor =
71 sv->
asA<SensorValue1DoFActuatorTorque>();
72 const SensorValue1DoFActuatorVelocity* velocitySensor =
73 sv->
asA<SensorValue1DoFActuatorVelocity>();
74 const SensorValue1DoFActuatorPosition* positionSensor =
75 sv->
asA<SensorValue1DoFActuatorPosition>();
82 ARMARX_WARNING <<
"No velocity sensor available for " << jointName;
86 ARMARX_WARNING <<
"No position sensor available for " << jointName;
89 torqueSensors.push_back(torqueSensor);
90 velocitySensors.push_back(velocitySensor);
91 positionSensors.push_back(positionSensor);
95 ftsensor.initialize(rns, robotUnit, cfg->controlParamJsonFile);
100 mplib::factories::VMPFactory mpfactory;
101 mpfactory.addConfig(
"kernelSize", 100);
102 mplib::representation::VMPType vmp_type =
103 mplib::representation::VMPType::PrincipalComponent;
104 std::shared_ptr<mplib::representation::AbstractMovementPrimitive> vmp =
105 mpfactory.createMP(vmp_type);
107 std::dynamic_pointer_cast<mplib::representation::vmp::PrincipalComponentVMP>(vmp);
110 common::FTSensor::FTBufferData ftData;
111 ftData.forceBaseline.setZero();
112 ftData.torqueBaseline.setZero();
113 ftData.enableTCPGravityCompensation = cfg->enableTCPGravityCompensation;
114 ftData.tcpMass = cfg->tcpMass;
115 ftData.tcpCoMInFTSensorFrame = cfg->tcpCoMInForceSensorFrame;
116 ftSensorBuffer.reinitAllBuffers(ftData);
118 law::TaskspaceKeypointsAdmittanceController::Config configData;
119 configData.kpImpedance = cfg->kpImpedance;
120 configData.kdImpedance = cfg->kdImpedance;
121 configData.kpAdmittance = cfg->kpAdmittance;
122 configData.kdAdmittance = cfg->kdAdmittance;
123 configData.kmAdmittance = cfg->kmAdmittance;
125 configData.kpNullspaceTorque = cfg->kpNullspaceTorque;
126 configData.kdNullspaceTorque = cfg->kdNullspaceTorque;
128 configData.currentForceTorque.setZero();
129 configData.desiredTCPPose = Eigen::Matrix4f::Identity();
130 configData.desiredTCPTwist.setZero();
131 configData.desiredNullspaceJointAngles = cfg->desiredNullspaceJointAngles;
133 configData.torqueLimit = cfg->torqueLimit;
134 configData.qvelFilter = cfg->qvelFilter;
139 configData.numPoints = cfg->numKeypoints;
141 configData.keypointKp = cfg->keypointKp;
142 configData.keypointKi = cfg->keypointKi;
143 configData.keypointKd = cfg->keypointKd;
144 configData.maxControlValue = cfg->maxControlValue;
145 configData.maxDerivation = cfg->maxDerivation;
147 configData.pointCtrlMask = cfg->pointCtrlMask;
148 configData.currentKeypointPosition = cfg->initialKeypointPosition;
149 configData.filteredKeypointPosition = cfg->initialKeypointPosition;
150 configData.desiredKeypointPosition = cfg->initialKeypointPosition;
151 configData.isRigid = cfg->isRigid;
152 configData.fixedTranslation.setZero(cfg->numKeypoints * 3);
155 numPoints = cfg->numKeypoints;
156 initialStateEigen = cfg->initialKeypointPosition;
158 controller.s.filteredKeypointPosition = cfg->initialKeypointPosition;
160 controller.s.fixedTranslation.setZero(cfg->numKeypoints * 3);
161 controller.s.currentKeypointPosition = cfg->initialKeypointPosition;
166 cfg->maxControlValue,
174 for (
int i = 0; i < cfg->numKeypoints * 3; i++)
176 mplib::core::DVec state;
177 state.push_back(cfg->initialKeypointPosition[i]);
178 state.push_back(0.0);
179 rt2mp.currentState.push_back(state);
182 rt2mpBuffer.reinitAllBuffers(rt2mp);
188 return "KeypointMPController";
194 return kinematicChainName;
199 const IceUtil::Time& timeSinceLastIteration)
204 timeSinceLastIteration,
211 for (
size_t i = 0; i < (unsigned)
controller.s.numPoints * 3; i++)
213 mplib::core::DVec state;
214 state.push_back(
controller.s.currentKeypointPosition[i]);
215 state.push_back(0.0);
216 rt2mpBuffer.getWriteBuffer().currentState[i] = state;
218 rt2mpBuffer.getWriteBuffer().deltaT =
controller.s.deltaT;
219 rt2mpBuffer.commitWrite();
221 controlStatusBuffer.getWriteBuffer().currentPose =
controller.s.currentPose;
222 controlStatusBuffer.getWriteBuffer().currentTwist =
controller.s.currentTwist * 1000.0f;
223 controlStatusBuffer.getWriteBuffer().deltaT =
controller.s.deltaT;
224 controlStatusBuffer.getWriteBuffer().currentKeypointPosition =
226 controlStatusBuffer.getWriteBuffer().desiredKeypointPosition =
228 controlStatusBuffer.commitWrite();
231 if (rtFirstRun.load())
233 rtFirstRun.store(
false);
234 rtReady.store(
false);
242 ftsensor.compensateTCPGravity(ftSensorBuffer.getReadBuffer());
255 ftsensor.getFilteredForceTorque(ftSensorBuffer.getReadBuffer());
260 const auto& desiredJointTorques =
controller.run(rtReady.load());
264 for (
size_t i = 0; i < targets.size(); ++i)
266 targets.at(i)->torque = desiredJointTorques(i);
267 if (!targets.at(i)->isValid())
269 targets.at(i)->torque = 0;
275 controlStatusBuffer.getWriteBuffer().kpImpedance =
controller.s.kpImpedance;
276 controlStatusBuffer.getWriteBuffer().kdImpedance =
controller.s.kdImpedance;
277 controlStatusBuffer.getWriteBuffer().forceImpedance =
controller.s.forceImpedance;
278 controlStatusBuffer.getWriteBuffer().currentForceTorque =
281 controlStatusBuffer.getWriteBuffer().virtualPose =
controller.s.virtualPose;
282 controlStatusBuffer.getWriteBuffer().desiredTCPPose =
controller.s.desiredTCPPose;
283 controlStatusBuffer.getWriteBuffer().virtualVel =
controller.s.virtualVel;
284 controlStatusBuffer.getWriteBuffer().virtualAcc =
controller.s.virtualAcc;
285 controlStatusBuffer.getWriteBuffer().currentKeypointPosition =
287 controlStatusBuffer.getWriteBuffer().desiredKeypointPosition =
289 controlStatusBuffer.getWriteBuffer().filteredKeypointPosition =
291 controlStatusBuffer.getWriteBuffer().pointTrackingForce =
293 controlStatusBuffer.commitWrite();
300 mpEnabled.store(enableMP);
307 return mpEnabled.load();
311 KeypointMPController::runMP()
313 if (!rtReady.load() && !mpEnabled.load())
323 if (canVal > 1e-8 && mpRunning.load())
325 double phaseStop = 0;
328 canVal -= tau * deltaT * 1 / ((1 + phaseStop) * timeDuration);
329 currentState = pointVMP->calculateDesiredState(canVal, currentState);
331 Eigen::VectorXf desiredPosition;
332 desiredPosition.setZero(currentState.size());
333 for (
size_t i = 0; i < currentState.size(); i++)
335 desiredPosition[i] = currentState[i][0];
355 const std::string& name,
356 const Eigen::Matrix4f& pose)
359 vec.head<3>() = pose.block<3, 1>(0, 3);
360 vec.tail<3>() = VirtualRobot::MathTools::eigen4f2rpy(pose);
366 const std::string& name,
369 datafields[name +
"_x"] =
new Variant(vec(0));
370 datafields[name +
"_y"] =
new Variant(vec(1));
371 datafields[name +
"_z"] =
new Variant(vec(2));
372 datafields[name +
"_rx"] =
new Variant(vec(3));
373 datafields[name +
"_ry"] =
new Variant(vec(4));
374 datafields[name +
"_rz"] =
new Variant(vec(5));
379 const std::string& name,
382 for (
int i = 0; i < vec.size(); i++)
384 datafields[name +
"_" + std::to_string(i)] =
new Variant(vec(i));
394 auto values = debugRTBuffer.getUpToDateReadBuffer().desired_torques;
395 for (
auto& pair : values)
397 datafields[pair.first] =
new Variant(pair.second);
472 datafields[
"currentKeypointPosition_x"] =
473 new Variant(controlStatusBuffer.getUpToDateReadBuffer().currentKeypointPosition(0));
474 datafields[
"currentKeypointPosition_y"] =
475 new Variant(controlStatusBuffer.getUpToDateReadBuffer().currentKeypointPosition(1));
476 datafields[
"currentKeypointPosition_z"] =
477 new Variant(controlStatusBuffer.getUpToDateReadBuffer().currentKeypointPosition(2));
482 datafields[
"desiredKeypointPosition_x"] =
483 new Variant(controlStatusBuffer.getUpToDateReadBuffer().desiredKeypointPosition(0));
484 datafields[
"desiredKeypointPosition_y"] =
485 new Variant(controlStatusBuffer.getUpToDateReadBuffer().desiredKeypointPosition(1));
486 datafields[
"desiredKeypointPosition_z"] =
487 new Variant(controlStatusBuffer.getUpToDateReadBuffer().desiredKeypointPosition(2));
492 datafields[
"filteredKeypointPosition_x"] =
493 new Variant(controlStatusBuffer.getUpToDateReadBuffer().filteredKeypointPosition(0));
494 datafields[
"filteredKeypointPosition_y"] =
495 new Variant(controlStatusBuffer.getUpToDateReadBuffer().filteredKeypointPosition(1));
496 datafields[
"filteredKeypointPosition_z"] =
497 new Variant(controlStatusBuffer.getUpToDateReadBuffer().filteredKeypointPosition(2));
499 datafields[
"track_force_x"] =
500 new Variant(controlStatusBuffer.getUpToDateReadBuffer().pointTrackingForce(0));
501 datafields[
"track_force_y"] =
502 new Variant(controlStatusBuffer.getUpToDateReadBuffer().pointTrackingForce(1));
503 datafields[
"track_force_z"] =
504 new Variant(controlStatusBuffer.getUpToDateReadBuffer().pointTrackingForce(2));
505 datafields[
"track_force_rx"] =
506 new Variant(controlStatusBuffer.getUpToDateReadBuffer().pointTrackingForce(3));
507 datafields[
"track_force_ry"] =
508 new Variant(controlStatusBuffer.getUpToDateReadBuffer().pointTrackingForce(4));
509 datafields[
"track_force_rz"] =
510 new Variant(controlStatusBuffer.getUpToDateReadBuffer().pointTrackingForce(5));
512 debugObs->setDebugChannel(
"KeypointMPController", datafields);
532 const Eigen::VectorXf& value,
536 if (name ==
"kpImpedance")
541 else if (name ==
"kdImpedance")
546 else if (name ==
"kpAdmittance")
551 else if (name ==
"kdAdmittance")
556 else if (name ==
"kmAdmittance")
561 else if (name ==
"kpNullspaceTorque")
566 else if (name ==
"kdNullspaceTorque")
573 ARMARX_ERROR << name <<
" is not supported by TaskSpaceAdmittanceController";
580 const Eigen::Vector3f& torqueBaseline,
583 ftSensorBuffer.getWriteBuffer().forceBaseline = forceBaseline;
584 ftSensorBuffer.getWriteBuffer().torqueBaseline = torqueBaseline;
585 ftSensorBuffer.commitWrite();
591 ftSensorBuffer.getWriteBuffer().enableTCPGravityCompensation =
true;
592 ftSensorBuffer.getWriteBuffer().tcpMass = mass;
593 ftSensorBuffer.commitWrite();
600 ftSensorBuffer.getWriteBuffer().enableTCPGravityCompensation =
true;
601 ftSensorBuffer.getWriteBuffer().tcpCoMInFTSensorFrame = tcpCoMInFTSensorFrame;
602 ftSensorBuffer.commitWrite();
608 rtReady.store(
false);
620 pointVMP->prepareExecution(goal, initialState, 1.0);
621 mplib::representation::MPStateVec initState =
622 mplib::core::SystemState::convert2DArrayToStates<mplib::representation::MPState>(
628 Ice::Double duration,
631 timeDuration = duration;
632 pointVMP->prepareExecution(goal, initialState, 1.0);
633 mplib::representation::MPStateVec initState =
634 mplib::core::SystemState::convert2DArrayToStates<mplib::representation::MPState>(
636 mpRunning.store(
true);
642 pointVMP->prepareExecution(goal, initialState, 1.0);
643 mplib::representation::MPStateVec initState =
644 mplib::core::SystemState::convert2DArrayToStates<mplib::representation::MPState>(
656 mpRunning.store(
false);
662 mpRunning.store(
false);
668 mpRunning.store(
true);
674 if (mpRunning.load())
684 return !mpRunning.load();
690 std::vector<mplib::core::SampledTrajectory> trajs;
691 for (
auto& file : fileList)
693 mplib::core::SampledTrajectory traj;
694 traj.readFromCSVFile(file);
695 trajs.push_back(traj);
697 pointVMP->learnFromTrajectories(trajs);
700 initialState.clear();
703 for (
size_t i = 0; i < trajs[0].dim(); i++)
705 mplib::core::DVec state;
708 state.push_back(initialStateEigen[i]);
709 state.push_back(0.0);
710 initialState.push_back(state);
711 goal.push_back(trajs[0].rbegin()->getPosition(i));
722 const Ice::DoubleSeq&,
744 return "notImplemented";
758 std::vector<double> dummy;
759 dummy.push_back(0.0);
772 ftSensorBuffer.getWriteBuffer().enableTCPGravityCompensation = toggle;
773 ftSensorBuffer.commitWrite();
774 rtReady.store(
false);
780 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(kinematicChainName);
781 Eigen::Matrix4f currentPose = rns->getTCP()->getPoseInRootFrame();
782 ARMARX_IMPORTANT <<
"rt preactivate controller with target pose\n\n" << currentPose;
785 controller.s.previousTargetPose = currentPose;
790 Eigen::VectorXf fixedTranslation;
791 fixedTranslation.setZero(
controller.s.currentKeypointPosition.size());
796 for (
int i = 0; i < numPoints; i++)
798 fixedTranslation.segment(3 * i, 3) =
799 controller.s.currentKeypointPosition.segment(3 * i, 3) -
800 currentPose.block<3, 1>(0, 3);
804 controller.s.fixedTranslation = fixedTranslation;
814 runTask(
"KeypointMPController",
820 while (
getState() == eManagedIceObjectStarted)
826 c.waitForCycleDuration();
836 keypointPosition.size());
843 const float keypoint_stiffness,
845 const Eigen::VectorXf& ctrl_mask,
846 const Eigen::VectorXf& init_keypoints_position,
849 numPoints = n_points;
Brief description of class JointControlTargetBase.
This util class helps with keeping a cycle time during a control cycle.
ArmarXObjectSchedulerPtr getObjectScheduler() const
int getState() const
Retrieve current state of the ManagedIceObject.
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
ControlTargetBase * useControlTarget(const std::string &deviceName, const std::string &controlMode)
Declares to calculate the ControlTarget for the given ControlDevice in the given ControlMode when rtR...
const law::TaskspaceKeypointsAdmittanceController::Config & rtGetControlStruct() const
MutexType controlDataMutex
std::lock_guard< std::recursive_mutex > LockGuardType
void writeControlStruct()
bool rtUpdateControlStruct()
law::TaskspaceKeypointsAdmittanceController::Config & getWriterControlStruct()
void reinitTripleBuffer(const law::TaskspaceKeypointsAdmittanceController::Config &initial)
The SensorValueBase class.
const T & getUpToDateReadBuffer() const
The Variant class is described here: Variants.
void resume(const Ice::Current &) override
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
void setGoal(const Ice::DoubleSeq &, const Ice::Current &) override
void onInitNJointController() override
Ice::Double getCanVal(const Ice::Current &) override
void stop(const Ice::Current &) override
void reconfigureController(const std::string &, const Ice::Current &) override
std::string getNames(const Ice::Current &) override
void start(const Ice::DoubleSeq &, const Ice::Current &) override
bool isFinished(const Ice::Current &) override
void learnFromCSV(const Ice::StringSeq &, const Ice::Current &) override
KeypointMPController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
void reset(const Ice::Current &) override
void resetKeypoints(const int n_points, const float keypoint_stiffness, const bool is_rigid, const Eigen::VectorXf &ctrl_mask, const Eigen::VectorXf &init_keypoints_position, const Ice::Current &) override
void setKeypoints(const Eigen::VectorXf &, const Ice::Current &) override
void pause(const Ice::Current &) override
void removeAllViaPoint(const Ice::Current &) override
void startAsTraj(const Ice::Current &) override
void toggleMP(const bool enableMP, const Ice::Current &) override
void setStartAndGoal(const Ice::DoubleSeq &, const Ice::DoubleSeq &, const Ice::Current &) override
void setForceTorqueBaseline(const Eigen::Vector3f &, const Eigen::Vector3f &, const Ice::Current &) override
bool getMPEnabled(const Ice::Current &) override
Ice::DoubleSeq deserialize(const std::string &mpAsString, const Ice::Current &) override
std::string getKinematicChainName(const Ice::Current &) override
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
void setTCPCoMInFTFrame(const Eigen::Vector3f &, const Ice::Current &) override
void publishPose(StringVariantBaseMap &datafields, const std::string &name, const Eigen::Matrix4f &pose)
std::string serialize(const Ice::Current &) override
void setViaPoint(Ice::Double, const Ice::DoubleSeq &, const Ice::Current &) override
void setTCPMass(Ice::Float, const Ice::Current &) override
void startAsTrajWithTime(Ice::Double, const Ice::Current &) override
void calibrateFTSensor(const Ice::Current &) override
void setTCPPose(const Eigen::Matrix4f &, const Ice::Current &) override
void startWithTime(const Ice::DoubleSeq &, Ice::Double, const Ice::Current &) override
void publishVec6f(StringVariantBaseMap &datafields, const std::string &name, const Eigen::Vector6f &vec)
void setControlParameters(const std::string &, const Eigen::VectorXf &, const Ice::Current &) override
set control parameter
std::string getClassName(const Ice::Current &) const override
void publishVecXf(StringVariantBaseMap &datafields, const std::string &name, const Eigen::Vector6f &vec)
void rtPreActivateController() override
This function is called before the controller is activated.
void toggleGravityCompensation(const bool toggle, const Ice::Current &) override
ft sensor
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#define ARMARX_INFO
The normal logging level.
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Matrix< float, 6, 1 > Vector6f
std::shared_ptr< class Robot > RobotPtr
This file is part of ArmarX.
NJointControllerRegistration< KeypointMPController > registrationControllerKeypointMPController("KeypointMPController")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
IceUtil::Handle< class RobotUnit > RobotUnitPtr
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl