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 ur5
Full code
15 #include "mujoco/mujoco_sim.h"
16 #include "Qontrol/Qontrol.hpp"
17 #include "trajectory_generation/trajectory_generation.h"
19 #define MUJOCO_PLUGIN_DIR "mujoco_plugin"
22 using namespace Qontrol;
24 class MujocoQontrol :
public MujocoSim
28 std::shared_ptr<Qontrol::Model::RobotModel<Qontrol::ModelImpl::PINOCCHIO>> model;
29 std::shared_ptr<Qontrol::JointVelocityProblem> velocity_problem;
30 std::shared_ptr<Qontrol::Task::GenericTask> custom_task;
31 pinocchio::SE3 init_pose;
35 TrajectoryGeneration* traj;
36 std::string resource_path;
37 void initController()
override
42 const int ndof = model->getNrOfDegreesOfFreedom();
44 velocity_problem = std::make_shared<Qontrol::JointVelocityProblem>(model);
46 custom_task = velocity_problem->task_set->add(
"CustomMainTask", 6, 1.0);
47 auto regularisation_task = velocity_problem->task_set->add<
Task::JointVelocity>(
"RegularisationTask",1e-5);
50 auto joint_velocity_constraint = velocity_problem->constraint_set->add<
Constraint::JointVelocity>(
"JointVelocityConstraint");
52 mju_copy(d->qpos, m->key_qpos, m->nu);
53 robot_state.joint_position.resize(ndof);
54 robot_state.joint_velocity.resize(ndof);
55 for (
int i=0; i<ndof ; ++i)
57 robot_state.joint_position[i] = d->qpos[i];
58 robot_state.joint_velocity[i] = d->qvel[i];
60 model->setRobotState(robot_state);
62 traj =
new TrajectoryGeneration(resource_path+
"trajectory.csv", m->opt.timestep);
66 void updateController()
override
68 const int ndof = model->getNrOfDegreesOfFreedom();
70 for (
int i=0; i<ndof ; ++i)
72 robot_state.joint_position[i] = d->qpos[i];
73 robot_state.joint_velocity[i] = d->qvel[i];
75 model->setRobotState(robot_state);
77 pinocchio::SE3 current_pose(model->getFramePose(model->getTipFrameName()).matrix());
79 pinocchio::SE3 traj_pose(traj->pose.matrix());
80 const pinocchio::SE3 tipMdes = current_pose.actInv(traj_pose);
81 auto err = pinocchio::log6(tipMdes).toVector();
82 Eigen::Matrix<double,6,1> p_gains;
83 p_gains << 10,10,10,10,10,10;
84 Eigen::Matrix<double,6,1> xd_star = p_gains.cwiseProduct(err);
85 custom_task->setE(model->getJacobian(model->getTipFrameName()));
86 custom_task->setf(xd_star);
87 velocity_problem->update(m->opt.timestep);
89 if (velocity_problem->solutionFound())
91 sendJointVelocity(velocity_problem->getJointVelocityCommand());
97 int main(
int argc,
const char** argv) {
98 MujocoQontrol mujoco_qontrol;
99 Qontrol::Log::Logger::parseArgv(argc, argv);
102 mjv_defaultScene(&scn);
105 mjv_defaultCamera(&cam);
108 mjv_defaultOption(&opt);
111 mjv_defaultPerturb(&pert);
114 auto sim = std::make_unique<mj::Simulate>(
115 std::make_unique<mj::GlfwAdapter>(), &cam, &opt, &pert,
true
118 std::string robot = argv[1];
119 std::string mujoco_model =
"./resources/"+robot+
"/scene.xml";
120 mujoco_qontrol.resource_path =
"./resources/"+robot+
"/";
123 std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_model);
127 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.
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
40 Model::RobotModel<ModelImpl::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.
45 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.
47 auto regularisation_task = velocity_problem->task_set->add<Task::JointVelocity>(
"RegularisationTask",1e-5);
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
49 auto joint_configuration_constraint = velocity_problem->constraint_set->add<Constraint::JointConfiguration>(
"JointConfigurationConstraint");
50 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.
52 mju_copy(d->qpos, m->key_qpos, m->nu);
53 robot_state.joint_position.resize(ndof);
54 robot_state.joint_velocity.resize(ndof);
55 for (
int i=0; i<ndof ; ++i)
57 robot_state.joint_position[i] = d->qpos[i];
58 robot_state.joint_velocity[i] = d->qvel[i];
60 model->setRobotState(robot_state);
We create the robot state and fill it with the simulated robot current state.
62 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
67 void updateController()
override
69 const int ndof = model->getNrOfDegreesOfFreedom();
71 for (
int i=0; i<ndof ; ++i)
73 robot_state.joint_position[i] = d->qpos[i];
74 robot_state.joint_velocity[i] = d->qvel[i];
76 model->setRobotState(robot_state);
78 pinocchio::SE3 current_pose(model->getFramePose(model->getTipFrameName()).matrix());
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.
80 pinocchio::SE3 traj_pose(traj->pose.matrix());
81 const pinocchio::SE3 tipMdes = current_pose.actInv(traj_pose);
82 auto err = pinocchio::log6(tipMdes).toVector();
83 Eigen::Matrix<double,6,1> p_gains;
84 p_gains << 10,10,10,10,10,10;
85 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.
86 custom_task->setE(model->getJacobian(model->getTipFrameName()));
87 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.
88 velocity_problem->update(m->opt.timestep);
90 if (velocity_problem->solutionFound())
92 sendJointVelocity(velocity_problem->getJointVelocityCommand());
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
98 int main(
int argc,
const char** argv) {
99 MujocoQontrol mujoco_qontrol;
100 Qontrol::Log::Logger::parseArgv(argc, argv);
103 mjv_defaultScene(&scn);
106 mjv_defaultCamera(&cam);
109 mjv_defaultOption(&opt);
112 mjv_defaultPerturb(&pert);
115 auto sim = std::make_unique<mj::Simulate>(
116 std::make_unique<mj::GlfwAdapter>(), &cam, &opt, &pert,
true
119 std::string robot = argv[1];
120 std::string mujoco_model =
"./resources/"+robot+
"/scene.xml";
121 mujoco_qontrol.resource_path =
"./resources/"+robot+
"/";
124 std::thread physicsthreadhandle( &MujocoQontrol::PhysicsThread, mujoco_qontrol, sim.get(), mujoco_model);
128 physicsthreadhandle.join();
The main function function fetches the robot name given in argv and starts the Mujoco simulation.