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
15 #include "mujoco/mujoco_sim.h"
16 #include "Qontrol/Qontrol.hpp"
17 #include "trajectory_generation/trajectory_generation.h"
20 using namespace Qontrol;
22 class MujocoQontrol :
public MujocoSim
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;
32 TrajectoryGeneration* traj;
33 std::string resource_path;
35 void initController()
override
40 acceleration_problem = std::make_shared<Qontrol::JointAccelerationProblem>(model);
42 auto regularisation_task = acceleration_problem->task_set->add<
Task::JointAcceleration>(
"RegularisationTask",1e-5);
45 auto joint_velocity_constraint = acceleration_problem->constraint_set->add<
Constraint::JointVelocity>(
"JointVelocityConstraint");
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());
51 traj =
new TrajectoryGeneration(resource_path +
"trajectory.csv",
55 void updateController()
override
58 for (
int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
60 robot_state.joint_position[i] = d->qpos[i];
61 robot_state.joint_velocity[i] = d->qvel[i];
63 model->setRobotState(robot_state);
66 pinocchio::SE3 traj_pose(traj->pose.matrix());
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())) +
80 main_task->setTargetAcceleration(xdd_star);
82 acceleration_problem->update(m->opt.timestep);
84 if (acceleration_problem->solutionFound())
86 sendJointVelocity(acceleration_problem->getJointVelocityCommand());
92 int main(
int argc,
const char** argv) {
93 MujocoQontrol mujoco_qontrol;
94 Qontrol::Log::Logger::parseArgv(argc, argv);
97 mjv_defaultCamera(&cam);
100 mjv_defaultOption(&opt);
103 mjv_defaultPerturb(&pert);
106 auto sim = std::make_unique<mj::Simulate>(
107 std::make_unique<mj::GlfwAdapter>(),
108 &cam, &opt, &pert,
false
111 std::string robot = argv[1];
112 std::string mujoco_scene =
"./resources/"+robot+
"/scene.xml";
113 mujoco_qontrol.resource_path =
"./resources/"+robot+
"/";
116 std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_scene.c_str());
120 physicsthreadhandle.join();
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
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.
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.
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());
51 traj =
new TrajectoryGeneration(resource_path +
"trajectory.csv",
55 void updateController()
override
58 for (
int i=0; i<model->getNrOfDegreesOfFreedom() ; ++i)
60 robot_state.joint_position[i] = d->qpos[i];
61 robot_state.joint_velocity[i] = d->qvel[i];
63 model->setRobotState(robot_state);
We create the robot state and fill it with the simulated robot current state.
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.