CartesianImpedanceController.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <Eigen/Geometry>
4 
5 #include <VirtualRobot/VirtualRobot.h>
6 
7 namespace armarx
8 {
9  class SensorValue1DoFActuatorTorque;
10  class SensorValue1DoFActuatorVelocity;
11  class SensorValue1DoFActuatorPosition;
12 
14  {
15  public:
16  struct Config
17  {
18  Eigen::Vector3f desiredPosition;
20  Eigen::Vector3f Kpos;
21  Eigen::Vector3f Dpos;
22  Eigen::Vector3f Kori;
23  Eigen::Vector3f Dori;
24  Eigen::VectorXf Knull;
25  Eigen::VectorXf Dnull;
26  Eigen::VectorXf desiredJointPosition;
27  float torqueLimit;
28  };
29 
30  //state for debugging
31  struct Debug
32  {
33  float errorAngle;
34  float posiError;
35  Eigen::Vector3f tcpDesiredForce;
36  Eigen::Vector3f tcpDesiredTorque;
37  };
38 
39  private:
40  Eigen::VectorXf qpos;
41  Eigen::VectorXf qvel;
42  Eigen::VectorXf tcptwist;
43  Eigen::VectorXf nullqerror;
44  Eigen::VectorXf nullspaceTorque;
45  Eigen::VectorXf targetJointTorques;
46 
47  Eigen::MatrixXf I;
48 
49  VirtualRobot::DifferentialIKPtr ik;
50  VirtualRobot::RobotNodePtr tcp;
51 
52  const float lambda = 2;
53 
54  public:
56 
57  int bufferSize() const;
58  void initialize(const VirtualRobot::RobotNodeSetPtr& rns);
59  const Eigen::VectorXf&
60  run(const Config& cfg,
61  std::vector<const SensorValue1DoFActuatorTorque*> torqueSensors,
62  std::vector<const SensorValue1DoFActuatorVelocity*> velocitySensors,
63  std::vector<const SensorValue1DoFActuatorPosition*> positionSensors);
64  };
65 } // namespace armarx
armarx::CartesianImpedanceController::Config::Kori
Eigen::Vector3f Kori
Definition: CartesianImpedanceController.h:22
armarx::CartesianImpedanceController::Debug
Definition: CartesianImpedanceController.h:31
armarx::CartesianImpedanceController::Config::Knull
Eigen::VectorXf Knull
Definition: CartesianImpedanceController.h:24
armarx::CartesianImpedanceController::Config::desiredJointPosition
Eigen::VectorXf desiredJointPosition
Definition: CartesianImpedanceController.h:26
armarx::CartesianImpedanceController::Config::Dnull
Eigen::VectorXf Dnull
Definition: CartesianImpedanceController.h:25
armarx::CartesianImpedanceController::run
const Eigen::VectorXf & run(const Config &cfg, std::vector< const SensorValue1DoFActuatorTorque * > torqueSensors, std::vector< const SensorValue1DoFActuatorVelocity * > velocitySensors, std::vector< const SensorValue1DoFActuatorPosition * > positionSensors)
Definition: CartesianImpedanceController.cpp:48
armarx::CartesianImpedanceController
Definition: CartesianImpedanceController.h:13
armarx::CartesianImpedanceController::bufferSize
int bufferSize() const
Definition: CartesianImpedanceController.cpp:22
armarx::CartesianImpedanceController::Config::torqueLimit
float torqueLimit
Definition: CartesianImpedanceController.h:27
armarx::CartesianImpedanceController::Config::Dpos
Eigen::Vector3f Dpos
Definition: CartesianImpedanceController.h:21
armarx::CartesianImpedanceController::Config::desiredOrientation
Eigen::Quaternionf desiredOrientation
Definition: CartesianImpedanceController.h:19
armarx::CartesianImpedanceController::Config::Dori
Eigen::Vector3f Dori
Definition: CartesianImpedanceController.h:23
armarx::CartesianImpedanceController::Config::desiredPosition
Eigen::Vector3f desiredPosition
Definition: CartesianImpedanceController.h:18
armarx::CartesianImpedanceController::Debug::errorAngle
float errorAngle
Definition: CartesianImpedanceController.h:33
armarx::CartesianImpedanceController::Config
Definition: CartesianImpedanceController.h:16
armarx::CartesianImpedanceController::initialize
void initialize(const VirtualRobot::RobotNodeSetPtr &rns)
Definition: CartesianImpedanceController.cpp:28
armarx::CartesianImpedanceController::Debug::posiError
float posiError
Definition: CartesianImpedanceController.h:34
armarx::Quaternion< float, 0 >
armarx::CartesianImpedanceController::Debug::tcpDesiredForce
Eigen::Vector3f tcpDesiredForce
Definition: CartesianImpedanceController.h:35
armarx::CartesianImpedanceController::dbg
Debug dbg
Definition: CartesianImpedanceController.h:55
armarx::CartesianImpedanceController::Debug::tcpDesiredTorque
Eigen::Vector3f tcpDesiredTorque
Definition: CartesianImpedanceController.h:36
armarx::CartesianImpedanceController::Config::Kpos
Eigen::Vector3f Kpos
Definition: CartesianImpedanceController.h:20
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27