Qontrol
Custom constraint

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 consists in following a simple trajectory defined in Cartesian space. The mujoco library is used to simulate the robot behaviour. In this example the joint velocity constraint is defined as a custom constraint, meaning that the user as to update the constraint manually.

Simulation

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

./QontrolCustomConstraint 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::CartesianVelocity<Qontrol::ControlOutput::JointVelocity>> main_task;
31 std::shared_ptr<Qontrol::Constraint::GenericConstraint> custom_constraint;
32 pinocchio::SE3 init_pose;
33 
34 Qontrol::RobotState robot_state;
35 
36 TrajectoryGeneration* traj;
37 std::string resource_path;
38 void initController() override
39 {
40  model =
42 
43  velocity_problem = std::make_shared<Qontrol::JointVelocityProblem>(model);
44  main_task = velocity_problem->task_set->add<Task::CartesianVelocity>("MainTask"); // <-- Based on the template given will implement correct task representation
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  custom_constraint =
49  velocity_problem->constraint_set->add("CustomConstraint",model->getNrOfDegreesOfFreedom());
50 
51  mju_copy(d->qpos, m->key_qpos, m->nu);
52  robot_state.joint_position.resize(model->getNrOfDegreesOfFreedom());
53  robot_state.joint_velocity.resize(model->getNrOfDegreesOfFreedom());
54  for (int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
55  {
56  robot_state.joint_position[i] = d->qpos[i];
57  robot_state.joint_velocity[i] = d->qvel[i];
58  }
59  model->setRobotState(robot_state);
60 
61  traj = new TrajectoryGeneration(resource_path+"trajectory.csv", m->opt.timestep);
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  main_task->setTargetVelocity(xd_star);
83  custom_constraint->setConstraintMatrix(Eigen::MatrixXd::Identity(
84  model->getNrOfDegreesOfFreedom(), model->getNrOfDegreesOfFreedom()));
85  custom_constraint->setUpperBounds(model->getJointVelocityLimits());
86  custom_constraint->setLowerBounds(-model->getJointVelocityLimits());
87  velocity_problem->update(m->opt.timestep);
88 
89  if (velocity_problem->solutionFound())
90  {
91  sendJointVelocity(velocity_problem->getJointVelocityCommand());
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  mjvScene scn;
102  mjv_defaultScene(&scn);
103 
104  mjvCamera cam;
105  mjv_defaultCamera(&cam);
106 
107  mjvOption opt;
108  mjv_defaultOption(&opt);
109 
110  mjvPerturb pert;
111  mjv_defaultPerturb(&pert);
112 
113  // simulate object encapsulates the UI
114  auto sim = std::make_unique<mj::Simulate>(
115  std::make_unique<mj::GlfwAdapter>(),
116  &scn, &cam, &opt, &pert, /* fully_managed = */ true
117  );
118 
119 
120  std::string robot = argv[1];
121  std::string mujoco_model = "./resources/"+robot+"/scene.xml";
122  mujoco_qontrol.resource_path = "./resources/"+robot+"/";
123 
124  // start physics thread
125  std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_model);
126 
127  // start simulation UI loop (blocking call)
128  sim->RenderLoop();
129  physicsthreadhandle.join();
130 
131  return 0;
132 }

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::CartesianVelocity<Qontrol::ControlOutput::JointVelocity>> main_task;

The main task is expressed as a Cartesian velocity task.

30 std::shared_ptr<Qontrol::Constraint::GenericConstraint> custom_constraint;

Here we declare the custom constraint as a GenericConstraint.

Initialization

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

During initialization we instantiate the model with the robot urdf.

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

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

44  main_task = velocity_problem->task_set->add<Task::CartesianVelocity>("MainTask"); // <-- Based on the template given will implement correct task representation
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 of velocity_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. 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.

46  auto joint_configuration_constraint = velocity_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");

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

48  custom_constraint =
49  velocity_problem->constraint_set->add("CustomConstraint",model->getNrOfDegreesOfFreedom());

Then we add our custom constraint. We give it a name to identify it and also the size of the constraint. This size will be used by Qontrol to resize the constraint set.

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

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

60 
61  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  main_task->setTargetVelocity(xd_star);

The desired Cartesian velocity is then fed to the main task.

84  custom_constraint->setConstraintMatrix(Eigen::MatrixXd::Identity(
85  model->getNrOfDegreesOfFreedom(), model->getNrOfDegreesOfFreedom()));
86  custom_constraint->setUpperBounds(model->getJointVelocityLimits());
87  custom_constraint->setLowerBounds(-model->getJointVelocityLimits());

Here we update the custom constraint. We first set the constraint matrix A to the identity matrix. Then we set the lower and upper bounds of the constraint with the robot joint velocity limits.

88  velocity_problem->update(m->opt.timestep);
89 
90  if (velocity_problem->solutionFound())
91  {
92  sendJointVelocity(velocity_problem->getJointVelocityCommand());
93  }
94 }
95 
96 };

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

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