Go to the documentation of this file.
5 #include <VirtualRobot/Robot.h>
6 #include <VirtualRobot/IK/DifferentialIK.h>
9 #include <dmp/representation/dmp/umitsmp.h>
20 #include <armarx/control/deprecated_njoint_mp_controller/task_space/ControllerInterface.h>
31 using ViaPoint = std::pair<double, DMP::DVec >;
61 float derivative = (error - lastError) /
dt;
62 float retVal = Kp * error + Kd * derivative;
68 using ConfigPtrT = NJointTaskSpaceDMPControllerConfigPtr;
72 std::string
getClassName(
const Ice::Current&)
const override;
79 void learnDMPFromFiles(
const Ice::StringSeq& fileNames,
const Ice::Current&)
override;
85 void runDMP(
const Ice::DoubleSeq& goals,
Ice::Double tau,
const Ice::Current&)
override;
92 void setGoals(
const Ice::DoubleSeq& goals,
const Ice::Current&)
override;
95 void setTorqueKp(
const StringFloatDictionary& torqueKp,
const Ice::Current&)
override;
99 void pauseDMP(
const Ice::Current&)
override;
100 void resumeDMP(
const Ice::Current&)
override;
102 void resetDMP(
const Ice::Current&)
override;
103 void stopDMP(
const Ice::Current&)
override;
107 return dmpCtrl->canVal;
110 std::vector<double>
createDMPFromString(
const std::string& dmpString,
const Ice::Current&)
override;
116 void setMPWeights(
const DoubleSeqSeq& weights,
const Ice::Current&)
override;
117 DoubleSeqSeq
getMPWeights(
const Ice::Current&)
override;
135 std::vector<std::string> jointNames;
136 struct DebugBufferData
138 StringFloatDictionary latestTargetVelocities;
139 StringFloatDictionary dmpTargets;
140 StringFloatDictionary currentPose;
141 double currentCanVal;
155 Eigen::VectorXf targetJointVels;
161 struct RTToControllerData
166 Eigen::VectorXf currentTwist;
175 TripleBuffer<RTToUserData> rt2UserData;
180 std::vector<const SensorValue1DoFActuatorTorque*> torqueSensors;
181 std::vector<const SensorValue1DoFGravityTorque*> gravityTorqueSensors;
182 std::vector<ControlTarget1DoFActuatorVelocity*> targets;
183 std::vector<const SensorValue1DoFActuatorVelocity*> velocitySensors;
184 std::vector<const SensorValue1DoFActuatorPosition*> positionSensors;
187 std::vector<pidController> torquePIDs;
189 std::string nodeSetName;
195 VirtualRobot::DifferentialIKPtr ik;
196 VirtualRobot::RobotNodePtr tcp;
197 VirtualRobot::RobotNodePtr refFrame;
201 NJointTaskSpaceDMPControllerConfigPtr cfg;
206 std::string debugName;
208 Eigen::VectorXf filtered_qvel;
209 Eigen::Vector3f filtered_position;
210 float vel_filter_factor;
211 float pos_filter_factor;
219 Eigen::VectorXf jointHighLimits;
220 Eigen::VectorXf jointLowLimits;
std::vector< ViaPoint > ViaPointsSet
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
void onInitNJointController() override
const VariantTypeId Float
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
std::vector< float > torqueKp
void runDMPWithTime(const Ice::DoubleSeq &goals, Ice::Double timeDuration, const Ice::Current &) override
void setLinearVelocityKd(Ice::Float kd, const Ice::Current &=Ice::emptyCurrent) override
void setAngularVelocityKp(Ice::Float kp, const Ice::Current &=Ice::emptyCurrent) override
void setTorqueKp(const StringFloatDictionary &torqueKp, const Ice::Current &) override
void setViaPoints(Ice::Double u, const Ice::DoubleSeq &viapoint, const Ice::Current &) override
std::string getClassName(const Ice::Current &) const override
void onDisconnectNJointController() override
Eigen::VectorXf calcIK(const Eigen::VectorXf &cartesianVel, const Eigen::VectorXf &nullspace, VirtualRobot::IKSolver::CartesianSelection mode)
double getCanVal(const Ice::Current &) override
Eigen::Vector6f targetTSVel
DoubleSeqSeq getMPWeights()
NJointControllerConfigPtr ConfigPtrT
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
std::pair< double, DMP::DVec > ViaPoint
std::vector< float > nullspaceJointVelocities
IceUtil::Handle< PeriodicTask< T > > pointer_type
Shared pointer type for convenience.
std::shared_ptr< CartesianVelocityController > CartesianVelocityControllerPtr
const VariantTypeId Double
void learnDMPFromFiles(const Ice::StringSeq &fileNames, const Ice::Current &) override
void rtPreActivateController() override
This function is called before the controller is activated.
void setLinearVelocityKp(Ice::Float kp, const Ice::Current &=Ice::emptyCurrent) override
VirtualRobot::IKSolver::CartesianSelection ModeFromIce(const NJointTaskSpaceDMPControllerMode::CartesianSelection mode)
void setMPWeights(const DoubleSeqSeq &weights, const Ice::Current &) override
std::vector< double > createDMPFromString(const std::string &dmpString, const Ice::Current &) override
armarx::core::time::DateTime Time
bool update(mongocxx::collection &coll, const nlohmann::json &query, const nlohmann::json &update)
void setAngularVelocityKd(Ice::Float kd, const Ice::Current &=Ice::emptyCurrent) override
NJointTSDMPController(const RobotUnitPtr &, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
void setSpeed(Ice::Double times, const Ice::Current &) override
std::vector< float > torqueKd
std::shared_ptr< TaskSpaceDMPController > TaskSpaceDMPControllerPtr
MatrixXX< 4, 4, float > Matrix4f
bool isFinished(const Ice::Current &) override
Eigen::Matrix4f targetPose
std::recursive_mutex MutexType
TYPEDEF_PTRS_HANDLE(DeprecatedNJointPeriodicTSDMPCompliantController)
VirtualRobot::IKSolver::CartesianSelection mode
The NJointTSDMPController class.
void setControllerTarget(Ice::Float avoidJointLimitsKp, NJointTaskSpaceDMPControllerMode::CartesianSelection mode, const Ice::Current &) override
void setNullspaceJointVelocities(const StringFloatDictionary &nullspaceJointVelocities, const Ice::Current &) override
void setGoals(const Ice::DoubleSeq &goals, const Ice::Current &) override
void runDMP(const Ice::DoubleSeq &goals, Ice::Double tau, const Ice::Current &) override
std::shared_ptr< class Robot > RobotPtr
void removeAllViaPoints()