Qontrol
Custom task

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

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

.

The robot main tasks is defined as a custom task and 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:

./velocityQontrol robot_name

where robot_name can be either panda or universal_robots_ur5e

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 #define MUJOCO_PLUGIN_DIR "mujoco_plugin"
20 
21 
22 using namespace Qontrol;
23 
24 class MujocoQontrol : public MujocoSim
25 {
26 public:
27 //------------------------------------------- simulation -------------------------------------------
28 std::shared_ptr<Qontrol::Model::RobotModel<Qontrol::Model::RobotModelImplType::PINOCCHIO>> model;
29 std::shared_ptr<Qontrol::JointVelocityProblem> velocity_problem;
30 std::shared_ptr<Qontrol::Task::GenericTask> custom_task;
31 pinocchio::SE3 init_pose;
32 
33 Qontrol::RobotState robot_state;
34 
35 TrajectoryGeneration* traj;
36 std::string resource_path;
37 void initController() override
38 {
39  model =
41 
42  velocity_problem = std::make_shared<Qontrol::JointVelocityProblem>(model);
43 
44  custom_task = velocity_problem->task_set->add("CustomMainTask", 6, 1.0);
45  auto regularisation_task = velocity_problem->task_set->add<Task::JointVelocity>("RegularisationTask",1e-5); // <-- Based on the template given will implement correct task representationn
46 
47  auto joint_configuration_constraint = velocity_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");
48  auto joint_velocity_constraint = velocity_problem->constraint_set->add<Constraint::JointVelocity>("JointVelocityConstraint");
49 
50  mju_copy(d->qpos, m->key_qpos, m->nu);
51  robot_state.joint_position.resize(model->getNrOfDegreesOfFreedom());
52  robot_state.joint_velocity.resize(model->getNrOfDegreesOfFreedom());
53  for (int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
54  {
55  robot_state.joint_position[i] = d->qpos[i];
56  robot_state.joint_velocity[i] = d->qvel[i];
57  }
58  model->setRobotState(robot_state);
59 
60  traj = new TrajectoryGeneration(resource_path+"trajectory.csv", m->opt.timestep);
61 
62 }
63 
64 void updateController() override
65 {
66 
67  for (int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
68  {
69  robot_state.joint_position[i] = d->qpos[i];
70  robot_state.joint_velocity[i] = d->qvel[i];
71  }
72  model->setRobotState(robot_state);
73 
74  pinocchio::SE3 current_pose(model->getFramePose(model->getTipFrameName()).matrix());
75  traj->update();
76  pinocchio::SE3 traj_pose(traj->pose.matrix());
77  const pinocchio::SE3 tipMdes = current_pose.actInv(traj_pose);
78  auto err = pinocchio::log6(tipMdes).toVector();
79  Eigen::Matrix<double,6,1> p_gains;
80  p_gains << 10,10,10,10,10,10;
81  Eigen::Matrix<double,6,1> xd_star = p_gains.cwiseProduct(err);
82  custom_task->setE(model->getJacobian(model->getTipFrameName()));
83  custom_task->setf(xd_star);
84  velocity_problem->update(m->opt.timestep);
85 
86  if (velocity_problem->solutionFound())
87  {
88  sendJointVelocity(velocity_problem->getJointVelocityCommand());
89  }
90 }
91 
92 };
93 
94 int main(int argc, const char** argv) {
95  MujocoQontrol mujoco_qontrol;
96  Qontrol::Log::Logger::parseArgv(argc, argv);
97 
98  mjvScene scn;
99  mjv_defaultScene(&scn);
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  &scn, &cam, &opt, &pert, /* fully_managed = */ true
114  );
115 
116  std::string robot = argv[1];
117  std::string mujoco_model = "./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_model);
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<Qontrol::Model::RobotModel<Qontrol::Model::RobotModelImplType::PINOCCHIO>> model;

We use pinocchio for our model library.

28 std::shared_ptr<Qontrol::JointVelocityProblem> velocity_problem;

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

29 std::shared_ptr<Qontrol::Task::GenericTask> custom_task;

Here we declare the custom type as a GenericTask.

Initialization

37 void initController() override
38 {
39  model =
40  Model::RobotModel<Model::RobotModelImplType::PINOCCHIO>::loadModelFromFile(resource_path+"robot.urdf");

During initialization we instantiate the model with the robot urdf.

41  velocity_problem = std::make_shared<Qontrol::JointVelocityProblem>(model);

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

43  custom_task = velocity_problem->task_set->add("CustomMainTask", 6, 1.0);

We fill the task set of velocity_problem with the custom task. We give it a name, the dimension of the task, and the relative weight relatively to the other tasks. Here the task is in Cartesian space so it uses 6 degrees of freedom. Since it is the main task it has a maximal priority relatively to the other tasks so we give it a weight of 1.

45  auto regularisation_task = velocity_problem->task_set->add<Task::JointVelocity>("RegularisationTask",1e-5); // <-- Based on the template given will implement correct task representationn

We then fill the task set with the regularisation task. In this example, the regularisation tasks is defined as a joint veloicty task. Its means that this task will minimize the overall robot joint veloicty. It is given a small weight so that it doesn't interfere with the main task

46 
47  auto joint_configuration_constraint = velocity_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");
48  auto joint_velocity_constraint = velocity_problem->constraint_set->add<Constraint::JointVelocity>("JointVelocityConstraint");

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

49 
50  mju_copy(d->qpos, m->key_qpos, m->nu);
51  robot_state.joint_position.resize(model->getNrOfDegreesOfFreedom());
52  robot_state.joint_velocity.resize(model->getNrOfDegreesOfFreedom());
53  for (int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
54  {
55  robot_state.joint_position[i] = d->qpos[i];
56  robot_state.joint_velocity[i] = d->qvel[i];
57  }
58  model->setRobotState(robot_state);

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

59 
60  traj = new TrajectoryGeneration(resource_path+"trajectory.csv", m->opt.timestep);

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

65 void updateController() override
66 {
67 
68  for (int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
69  {
70  robot_state.joint_position[i] = d->qpos[i];
71  robot_state.joint_velocity[i] = d->qvel[i];
72  }
73  model->setRobotState(robot_state);
74 
75  pinocchio::SE3 current_pose(model->getFramePose(model->getTipFrameName()).matrix());
76  traj->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.

77  pinocchio::SE3 traj_pose(traj->pose.matrix());
78  const pinocchio::SE3 tipMdes = current_pose.actInv(traj_pose);
79  auto err = pinocchio::log6(tipMdes).toVector();
80  Eigen::Matrix<double,6,1> p_gains;
81  p_gains << 10,10,10,10,10,10;
82  Eigen::Matrix<double,6,1> xd_star = p_gains.cwiseProduct(err);

We then compute the desired Cartesian velocity using a simple proportionnal 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 are the proportionnal gains of the controller.

83  custom_task->setE(model->getJacobian(model->getTipFrameName()));
84  custom_task->setf(xd_star);

We then update the terms of the custom task. The E matrix is equal to the current robot Jacobian matrix expressed at the tip of the robot. The f term is the desired Cartesian velocity computed previously.

85  velocity_problem->update(m->opt.timestep);
86 
87  if (velocity_problem->solutionFound())
88  {
89  sendJointVelocity(velocity_problem->getJointVelocityCommand());
90  }
91 }
92 
93 };

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

94 
95 int main(int argc, const char** argv) {
96  MujocoQontrol mujoco_qontrol;
97  Qontrol::Log::Logger::parseArgv(argc, argv);
98 
99  mjvScene scn;
100  mjv_defaultScene(&scn);
101 
102  mjvCamera cam;
103  mjv_defaultCamera(&cam);
104 
105  mjvOption opt;
106  mjv_defaultOption(&opt);
107 
108  mjvPerturb pert;
109  mjv_defaultPerturb(&pert);
110 
111  // simulate object encapsulates the UI
112  auto sim = std::make_unique<mj::Simulate>(
113  std::make_unique<mj::GlfwAdapter>(),
114  &scn, &cam, &opt, &pert, /* fully_managed = */ true
115  );
116 
117  std::string robot = argv[1];
118  std::string mujoco_model = "./resources/"+robot+"/scene.xml";
119  mujoco_qontrol.resource_path = "./resources/"+robot+"/";
120 
121  // start physics thread
122  std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_model);
123 
124  // start simulation UI loop (blocking call)
125  sim->RenderLoop();
126  physicsthreadhandle.join();
127 
128  return 0;

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

Qontrol::RobotState
Robot state.
Definition: GenericModel.hpp:32
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:437
Qontrol::Task::JointVelocity
Implemtentation of a joint velocity task.
Definition: JointVelocity.hpp:35
Qontrol::Constraint::JointConfiguration
Implemtentation of a joint configuration constraint.
Definition: JointConfiguration.hpp:35