Qontrol
Torque control

The following example solves a qp problem expressed at the torque level such that:

\begin{equation}\begin{array}{ccc}\boldsymbol{\tau}^{opt} = & \underset{\boldsymbol{\tau}}{\mathrm{argmin}} & ||\boldsymbol{\dot{v}}(\boldsymbol{\tau}) - \boldsymbol{\dot{v}}^{target} || + \omega || \boldsymbol{\tau} - (\boldsymbol{g} - \boldsymbol{\dot{q}})||^2_{M^{-1}}\\& \textrm{s.t.} & \boldsymbol{\tau^{min}} \leq \boldsymbol{\tau} \leq \boldsymbol{\tau^{max}}. \\ & & \boldsymbol{q}^{min} \leq \boldsymbol{q}(\boldsymbol\tau) \leq \boldsymbol{q}^{max} \\ & & \boldsymbol{\dot{q}}^{min} \leq \boldsymbol{\dot{q}}(\boldsymbol\tau) \leq \boldsymbol{\dot{q}}^{max} \end{array} \end{equation}

.

The robot main tasks consists in following a simple trajectory defined in Cartesian space. The mujoco library is used to simulate the robot behaviour.

Simulation

To run this example run the following command from the build/examples directory:

./torqueQontrol robot_name

where robot_name can be either panda or ur5

Full code

1 // Copyright 2021 DeepMind Technologies Limited
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "mujoco/mujoco_sim.h"
16 #include "Qontrol/Qontrol.hpp"
17 #include "trajectory_generation/trajectory_generation.h"
18 
19 using namespace Qontrol;
20 
21 class MujocoQontrol : public MujocoSim
22 {
23 public:
24 //------------------------------------------- simulation -------------------------------------------
25 std::shared_ptr<Model::RobotModel<ModelImpl::PINOCCHIO>> model;
26 std::shared_ptr<JointTorqueProblem> torque_problem;
27 std::shared_ptr<Task::CartesianAcceleration<ControlOutput::JointTorque>> main_task;
28 std::shared_ptr<Task::JointTorque<ControlOutput::JointTorque>> regularisation_task;
29 
30 Qontrol::RobotState robot_state;
31 TrajectoryGeneration* traj;
32 std::string resource_path;
33 
34 void initController() override
35 {
36  model =
38 
39  const int ndof = model->getNrOfDegreesOfFreedom();
40 
41  torque_problem = std::make_shared<Qontrol::JointTorqueProblem>(model);
42  main_task = torque_problem->task_set->add<Task::CartesianAcceleration>("MainTask");
43  regularisation_task = torque_problem->task_set->add<Task::JointTorque>("RegularisationTask",1e-5);
44 
45  auto joint_configuration_constraint = torque_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");
46  auto joint_velocity_constraint = torque_problem->constraint_set->add<Constraint::JointVelocity>("JointVelocityConstraint");
47  auto joint_torque_constraint = torque_problem->constraint_set->add<Constraint::JointTorque>("JointTorqueConstraint");
48 
49  mju_copy(d->qpos, m->key_qpos, m->nu);
50  robot_state.joint_position.resize(ndof);
51  robot_state.joint_velocity.resize(ndof);
52 
53  traj = new TrajectoryGeneration(resource_path+"trajectory.csv", m->opt.timestep);
54 }
55 
56 void updateController() override
57 {
58  const int ndof = model->getNrOfDegreesOfFreedom();
59 
60  for (int i=0; i<ndof ; ++i)
61  {
62  robot_state.joint_position[i] = d->qpos[i];
63  robot_state.joint_velocity[i] = d->qvel[i];
64  }
65  model->setRobotState(robot_state);
66 
67  traj->update();
68  pinocchio::SE3 traj_pose(traj->pose.matrix());
69 
70  pinocchio::SE3 current_pose(model->getFramePose(model->getTipFrameName()).matrix());
71  const pinocchio::SE3 tipMdes = current_pose.actInv(traj_pose);
72  auto err = pinocchio::log6(tipMdes).toVector();
73 
74  Eigen::Matrix<double, 6, 1> p_gains;
75  p_gains << 1000, 1000, 1000, 1000, 1000, 1000;
76 
77  Eigen::Matrix<double, 6, 1> d_gains = 2.0 * p_gains.cwiseSqrt();
78  Eigen::Matrix<double, 6, 1> xdd_star =
79  p_gains.cwiseProduct(err) +
80  d_gains.cwiseProduct(traj->velocity - model->getFrameVelocity(model->getTipFrameName())) + traj->acceleration;
81 
82  main_task->setTargetAcceleration(xdd_star);
83  regularisation_task->setTargetTorque(model->getJointGravityTorques() -
84  robot_state.joint_velocity);
85  regularisation_task->setWeightingMatrix(
86  model->getInverseJointInertiaMatrix());
87  torque_problem->update(m->opt.timestep);
88 
89  if (torque_problem->solutionFound())
90  {
91  sendJointTorque(torque_problem->getJointTorqueCommand());
92  }
93 }
94 };
95 
96 
97 int main(int argc, const char** argv) {
98  MujocoQontrol mujoco_qontrol;
99  Qontrol::Log::Logger::parseArgv(argc, argv);
100 
101  mjvCamera cam;
102  mjv_defaultCamera(&cam);
103 
104  mjvOption opt;
105  mjv_defaultOption(&opt);
106 
107  mjvPerturb pert;
108  mjv_defaultPerturb(&pert);
109 
110  // simulate object encapsulates the UI
111  auto sim = std::make_unique<mj::Simulate>(
112  std::make_unique<mj::GlfwAdapter>(),
113  &cam, &opt, &pert, /* is_passive = */ false
114  );
115 
116  std::string robot = argv[1];
117  std::string mujoco_scene = "./resources/"+robot+"/scene.xml";
118  mujoco_qontrol.resource_path = "./resources/"+robot+"/";
119 
120  // start physics thread
121  std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_scene.c_str());
122 
123  // start simulation UI loop (blocking call)
124  sim->RenderLoop();
125  physicsthreadhandle.join();
126 
127  return 0;
128 }

Explanation of the code

Declaration

First we declare all the objects that will be used to define our problem.

0 std::shared_ptr<Model::RobotModel<ModelImpl::PINOCCHIO>> model;

We use pinocchio for our model library.

25 std::shared_ptr<JointTorqueProblem> torque_problem;

The output of our qp controller is at the torque level.

26 std::shared_ptr<Task::CartesianAcceleration<ControlOutput::JointTorque>> main_task;

We then declare two tasks that will be updated every milliseconds.

The main task is expressed as a Cartesian Acceleration task.

27 std::shared_ptr<Task::JointTorque<ControlOutput::JointTorque>> regularisation_task;

And we add a regularisation task (also at the torque level).

Initialization

34 void initController() override
35 {
36  model =
37  Model::RobotModel<ModelImpl::PINOCCHIO>::loadModelFromFile(resource_path+"robot.urdf");

During initialization we instantiate the model with the robot urdf.

We initialize the problem by giving it the model. By default, the qpmad library is used.

38 
39  const int ndof = model->getNrOfDegreesOfFreedom();
40 
41  torque_problem = std::make_shared<Qontrol::JointTorqueProblem>(model);
42  main_task = torque_problem->task_set->add<Task::CartesianAcceleration>("MainTask");
43  regularisation_task = torque_problem->task_set->add<Task::JointTorque>("RegularisationTask",1e-5);

We then fill the task set of torque_problem with the main task and the regularisation task. Each tasks is given a name and a relative weight \( \omega \). This weight can be modified at any time.

44 
45  auto joint_configuration_constraint = torque_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");
46  auto joint_velocity_constraint = torque_problem->constraint_set->add<Constraint::JointVelocity>("JointVelocityConstraint");
47  auto joint_torque_constraint = torque_problem->constraint_set->add<Constraint::JointTorque>("JointTorqueConstraint");

We then fill the constraint set of torque_problem with the three pre-implemented constraints. Each constraint is given a name. These constraints will automatically be updated during the update of Qontrol.

48 
49  mju_copy(d->qpos, m->key_qpos, m->nu);
50  robot_state.joint_position.resize(ndof);
51  robot_state.joint_velocity.resize(ndof);
52 
53  traj = new TrajectoryGeneration(resource_path+"trajectory.csv", m->opt.timestep);
54 }
55 
56 void updateController() override
57 {
58  const int ndof = model->getNrOfDegreesOfFreedom();
59 
60  for (int i=0; i<ndof ; ++i)
61  {
62  robot_state.joint_position[i] = d->qpos[i];
63  robot_state.joint_velocity[i] = d->qvel[i];
64  }
65  model->setRobotState(robot_state);

We also create the robot state and fill it with the simulated robot current state.

66 
67  traj->update();

We create a simple trajectory that has been precalculated and store in a csv file. This trajectory start at the robot current Cartesian pose and does a translation of (-0.1, -0,1, -0.1) m.

Update

The update function is called every milliseconds. At the beginning of each update we fill the new robot state according to the simulated robot.

We also update the trajectory so that it gives the next Cartesian pose to reach in 1 ms.

We then compute the desired Cartesian acceleration using a simple PD controller. Pinocchio is used to compute the error between the desired Cartesian pose and the current Cartesian pose. This is done by the log6 function. The p_gains and d_gains variables are the gains of the PD controller.

The desired Cartesian acceleration is then fed to the main task. The regularisation task is also updated so that it compensate for gravity plus a damping term. The resulting regularisation task would be written : \( || \boldsymbol{\tau} - (\boldsymbol{g} - \boldsymbol{\dot{q}})||^2_{M^{-1}}\)

Once we updated the necassary tasks and constraints we can update the whole problem. If a solution to the problem exist we can then get it and send it to the simulated robot.

Main function

The main function function fetches the robot name given in argv and starts the Mujoco simulation.

Qontrol::Task::CartesianAcceleration
Implementation of a Cartesian Acceleration task.
Definition: CartesianAcceleration.hpp:34
Qontrol::RobotState
Robot state.
Definition: GenericModel.hpp:35
Qontrol::Constraint::JointTorque
Implemtentation of a joint torque constraint.
Definition: JointTorque.hpp:34
Qontrol::Task::JointTorque
Implemtentation of a joint torque task.
Definition: JointTorque.hpp:34
Qontrol::Constraint::JointVelocity
Implemtentation of a joint velocity constraint.
Definition: JointVelocity.hpp:35
Qontrol::Model::RobotModel
Decalaration of a template specialization for the model library.
Definition: GenericModel.hpp:488
Qontrol::Constraint::JointConfiguration
Implemtentation of a joint configuration constraint.
Definition: JointConfiguration.hpp:35