This example shows how to build a reduced robot model from an existing URDF model by fixing the desired joints at a specified position.
Python
import pinocchio as pin
import numpy as np
from os.path import *
pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))), "models")
model_path = pinocchio_model_dir + '/example-robot-data/robots'
mesh_dir = pinocchio_model_dir
urdf_filename = model_path + '/ur_description/urdf/ur5_robot.urdf'
model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_filename, mesh_dir)
print('standard model: dim=' + str(len(model.joints)))
for jn in model.joints:
print(jn)
print('-' * 30)
jointsToLock = ['wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
jointsToLockIDs = []
for jn in jointsToLock:
if model.existJointName(jn):
jointsToLockIDs.append(model.getJointId(jn))
else:
print('Warning: joint ' + str(jn) + ' does not belong to the model!')
initialJointConfig = np.array([0,0,0,
1,1,1])
model_reduced = pin.buildReducedModel(model, jointsToLockIDs, initialJointConfig)
model_reduced, visual_model_reduced = pin.buildReducedModel(
model, visual_model, jointsToLockIDs, initialJointConfig)
geom_models = [visual_model, collision_model]
model_reduced, geometric_models_reduced = pin.buildReducedModel(
model,
list_of_geom_models=geom_models,
list_of_joints_to_lock=jointsToLockIDs,
reference_configuration=initialJointConfig)
visual_model_reduced, collision_model_reduced = geometric_models_reduced[
0], geometric_models_reduced[1]
print('joints to lock (only ids):', jointsToLockIDs)
print('reduced model: dim=' + str(len(model_reduced.joints)))
print('-' * 30)
mixed_jointsToLockIDs = [jointsToLockIDs[0], 'wrist_2_joint', 'wrist_3_joint']
robot = pin.RobotWrapper.BuildFromURDF(urdf_filename, mesh_dir)
reduced_robot = robot.buildReducedRobot(list_of_joints_to_lock=mixed_jointsToLockIDs,
reference_configuration=initialJointConfig)
print('mixed joints to lock (names and ids):', mixed_jointsToLockIDs)
print('RobotWrapper reduced model: dim=' + str(len(reduced_robot.model.joints)))
for jn in robot.model.joints:
print(jn)
C++
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"
#include "pinocchio/algorithm/model.hpp"
#include <iostream>
#include <algorithm>
#ifndef PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
#endif
template<typename T>
bool is_in_vector(const std::vector<T> & vector, const T & elt)
{
return vector.end() != std::find(vector.begin(),vector.end(),elt);
}
int main(int argc, char ** argv)
{
const std::string urdf_filename = (argc<=1) ? PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/ur_description/urdf/ur5_robot.urdf") : argv[1];
std::vector<std::string> list_of_joints_to_lock_by_name;
list_of_joints_to_lock_by_name.push_back("elbow_joint");
list_of_joints_to_lock_by_name.push_back("wrist_3_joint");
list_of_joints_to_lock_by_name.push_back("wrist_2_joint");
list_of_joints_to_lock_by_name.push_back("blabla");
std::vector<JointIndex> list_of_joints_to_lock_by_id;
for(std::vector<std::string>::const_iterator it = list_of_joints_to_lock_by_name.begin();
it != list_of_joints_to_lock_by_name.end(); ++it)
{
const std::string & joint_name = *it;
list_of_joints_to_lock_by_id.push_back(model.
getJointId(joint_name));
else
std::cout << "joint: " << joint_name << " does not belong to the model" << std::endl;
}
Eigen::VectorXd q_neutral=
neutral(model);
PINOCCHIO_UNUSED_VARIABLE(q_neutral);
std::cout << "\n\nFIRST CASE: BUILD A REDUCED MODEL FROM A LIST OF JOINT TO LOCK" << std::endl;
std::cout << "List of joints in the original model:" << std::endl;
for(JointIndex joint_id = 1; joint_id < model.
joints.size(); ++joint_id)
std::cout <<
"\t- " << model.
names[joint_id] << std::endl;
std::cout << "List of joints in the reduced model:" << std::endl;
for(JointIndex joint_id = 1; joint_id < reduced_model.
joints.size(); ++joint_id)
std::cout <<
"\t- " << reduced_model.
names[joint_id] << std::endl;
std::cout << "\n\nSECOND CASE: BUILD A REDUCED MODEL FROM A LIST OF JOINT TO KEEP UNLOCKED" << std::endl;
std::vector<std::string> list_of_joints_to_keep_unlocked_by_name;
list_of_joints_to_keep_unlocked_by_name.push_back("shoulder_pan_joint");
list_of_joints_to_keep_unlocked_by_name.push_back("shoulder_lift_joint");
list_of_joints_to_keep_unlocked_by_name.push_back("wrist_1_joint");
std::vector<JointIndex> list_of_joints_to_keep_unlocked_by_id;
for(std::vector<std::string>::const_iterator it = list_of_joints_to_keep_unlocked_by_name.begin();
it != list_of_joints_to_keep_unlocked_by_name.end(); ++it)
{
const std::string & joint_name = *it;
list_of_joints_to_keep_unlocked_by_id.push_back(model.
getJointId(joint_name));
else
std::cout << "joint: " << joint_name << " does not belong to the model";
}
list_of_joints_to_lock_by_id.clear();
for(JointIndex joint_id = 1; joint_id < model.
joints.size(); ++joint_id)
{
const std::string joint_name = model.
names[joint_id];
if(is_in_vector(list_of_joints_to_keep_unlocked_by_name,joint_name))
continue;
else
{
list_of_joints_to_lock_by_id.push_back(joint_id);
}
}
std::cout << "List of joints in the second reduced model:" << std::endl;
for(JointIndex joint_id = 1; joint_id < reduced_model2.
joints.size(); ++joint_id)
std::cout <<
"\t- " << reduced_model2.
names[joint_id] << std::endl;
}