Qontrol
Acceleration control

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

\begin{equation}\begin{array}{ccc}\boldsymbol{\ddot{q}}^{opt} = & \underset{\boldsymbol{\ddot{q}}}{\mathrm{argmin}} & ||J(\boldsymbol{q})\boldsymbol{\ddot{q}} + \dot{J}(\boldsymbol{q},\boldsymbol{\dot{q}})\boldsymbol{\dot{q}} - \boldsymbol{\dot{v}}^{target} || + \omega || \boldsymbol{\ddot{q}} ||^2\\& \textrm{s.t.} & \boldsymbol{\dot{q}^{min}} \leq \boldsymbol{\dot{q}}(\boldsymbol{\ddot{q}}) \leq \boldsymbol{\dot{q}^{max}}. \\ & & \boldsymbol{q}^{min} \leq \boldsymbol{q}(\boldsymbol{\ddot{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.

Simulation

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

./accelerationQontrol 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 
20 using namespace Qontrol;
21 
22 class MujocoQontrol : public MujocoSim
23 {
24 public:
25 //------------------------------------------- simulation -------------------------------------------
26 std::shared_ptr<Qontrol::Model::RobotModel<Qontrol::ModelImpl::PINOCCHIO>> model;
27 std::shared_ptr<Qontrol::JointAccelerationProblem> acceleration_problem;
28 std::shared_ptr<Qontrol::Task::CartesianAcceleration<ControlOutput::JointAcceleration>> main_task;
29 
30 Qontrol::RobotState robot_state;
31 
32 TrajectoryGeneration* traj;
33 std::string resource_path;
34 
35 void initController() override
36 {
37  model =
39 
40  acceleration_problem = std::make_shared<Qontrol::JointAccelerationProblem>(model);
41  main_task = acceleration_problem->task_set->add<Task::CartesianAcceleration>("MainTask");
42  auto regularisation_task = acceleration_problem->task_set->add<Task::JointAcceleration>("RegularisationTask",1e-5);
43 
44  auto joint_configuration_constraint = acceleration_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");
45  auto joint_velocity_constraint = acceleration_problem->constraint_set->add<Constraint::JointVelocity>("JointVelocityConstraint");
46 
47  mju_copy(d->qpos, m->key_qpos, m->nu);
48  robot_state.joint_position.resize(model->getNrOfDegreesOfFreedom());
49  robot_state.joint_velocity.resize(model->getNrOfDegreesOfFreedom());
50 
51  traj = new TrajectoryGeneration(resource_path + "trajectory.csv",
52  m->opt.timestep);
53 }
54 
55 void updateController() override
56 {
57 
58  for (int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
59  {
60  robot_state.joint_position[i] = d->qpos[i];
61  robot_state.joint_velocity[i] = d->qvel[i];
62  }
63  model->setRobotState(robot_state);
64 
65  traj->update();
66  pinocchio::SE3 traj_pose(traj->pose.matrix());
67 
68  pinocchio::SE3 current_pose(model->getFramePose(model->getTipFrameName()).matrix());
69  const pinocchio::SE3 tipMdes = current_pose.actInv(traj_pose);
70  auto err = pinocchio::log6(tipMdes).toVector();
71  Eigen::Matrix<double, 6, 1> p_gains;
72  p_gains << 1000, 1000, 1000, 1000, 1000, 1000;
73  Eigen::Matrix<double, 6, 1> d_gains = 2.0 * p_gains.cwiseSqrt();
74  Eigen::Matrix<double, 6, 1> xdd_star =
75  p_gains.cwiseProduct(err) +
76  d_gains.cwiseProduct(traj->velocity -
77  model->getFrameVelocity(model->getTipFrameName())) +
78  traj->acceleration;
79 
80  main_task->setTargetAcceleration(xdd_star);
81 
82  acceleration_problem->update(m->opt.timestep);
83 
84  if (acceleration_problem->solutionFound())
85  {
86  sendJointVelocity(acceleration_problem->getJointVelocityCommand());
87  }
88 }
89 
90 };
91 
92 int main(int argc, const char** argv) {
93  MujocoQontrol mujoco_qontrol;
94  Qontrol::Log::Logger::parseArgv(argc, argv);
95 
96  mjvCamera cam;
97  mjv_defaultCamera(&cam);
98 
99  mjvOption opt;
100  mjv_defaultOption(&opt);
101 
102  mjvPerturb pert;
103  mjv_defaultPerturb(&pert);
104 
105  // simulate object encapsulates the UI
106  auto sim = std::make_unique<mj::Simulate>(
107  std::make_unique<mj::GlfwAdapter>(),
108  &cam, &opt, &pert, /* is_passive = */ false
109  );
110 
111  std::string robot = argv[1];
112  std::string mujoco_scene = "./resources/"+robot+"/scene.xml";
113  mujoco_qontrol.resource_path = "./resources/"+robot+"/";
114 
115  // start physics thread
116  std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_scene.c_str());
117 
118  // start simulation UI loop (blocking call)
119  sim->RenderLoop();
120  physicsthreadhandle.join();
121 
122  return 0;
123 }

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::ModelImpl::PINOCCHIO>> model;

We use pinocchio for our model library.

26 std::shared_ptr<Qontrol::JointAccelerationProblem> acceleration_problem;

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

27 std::shared_ptr<Qontrol::Task::CartesianAcceleration<ControlOutput::JointAcceleration>> main_task;

The main task is expressed as a Cartesian acceleration task.

Initialization

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

During initialization we instantiate the model with the robot urdf.

39  acceleration_problem = std::make_shared<Qontrol::JointAccelerationProblem>(model);

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

41  main_task = acceleration_problem->task_set->add<Task::CartesianAcceleration>("MainTask");
42  auto regularisation_task = acceleration_problem->task_set->add<Task::JointAcceleration>("RegularisationTask",1e-5);

We then fill the task set of acceleration_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 acceleration task. Its means that this task will minimize the overall robot joint acceleration.

43 
44  auto joint_configuration_constraint = acceleration_problem->constraint_set->add<Constraint::JointConfiguration>("JointConfigurationConstraint");
45  auto joint_velocity_constraint = acceleration_problem->constraint_set->add<Constraint::JointVelocity>("JointVelocityConstraint");

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

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

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

64 
65  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 derivate 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 and the d_gains are the derivate gains of the controller.

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

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::Task::JointAcceleration
Implemtentation of a joint acceleration task.
Definition: JointAcceleration.hpp:35
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