1 #include "pinocchio/parsers/urdf.hpp" 3 #include "pinocchio/algorithm/joint-configuration.hpp" 4 #include "pinocchio/algorithm/model.hpp" 10 #ifndef PINOCCHIO_MODEL_DIR 11 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 17 return vector.end() != std::find(vector.begin(),vector.end(),elt);
20 int main(
int argc,
char ** argv)
32 std::vector<std::string> list_of_joints_to_lock_by_name;
33 list_of_joints_to_lock_by_name.push_back(
"elbow_joint");
34 list_of_joints_to_lock_by_name.push_back(
"wrist_3_joint");
35 list_of_joints_to_lock_by_name.push_back(
"wrist_2_joint");
36 list_of_joints_to_lock_by_name.push_back(
"blabla");
39 std::vector<JointIndex> list_of_joints_to_lock_by_id;
40 for(std::vector<std::string>::const_iterator it = list_of_joints_to_lock_by_name.begin();
41 it != list_of_joints_to_lock_by_name.end(); ++it)
45 list_of_joints_to_lock_by_id.push_back(model.
getJointId(joint_name));
47 std::cout <<
"joint: " << joint_name <<
" does not belong to the model" << std::endl;
58 std::cout <<
"\n\nFIRST CASE: BUILD A REDUCED MODEL FROM A LIST OF JOINT TO LOCK" << std::endl;
63 std::cout <<
"List of joints in the original model:" << std::endl;
68 std::cout <<
"List of joints in the reduced model:" << std::endl;
70 std::cout <<
"\t- " << reduced_model.
names[
joint_id] << std::endl;
72 std::cout <<
"\n\nSECOND CASE: BUILD A REDUCED MODEL FROM A LIST OF JOINT TO KEEP UNLOCKED" << std::endl;
74 std::vector<std::string> list_of_joints_to_keep_unlocked_by_name;
75 list_of_joints_to_keep_unlocked_by_name.push_back(
"shoulder_pan_joint");
76 list_of_joints_to_keep_unlocked_by_name.push_back(
"shoulder_lift_joint");
77 list_of_joints_to_keep_unlocked_by_name.push_back(
"wrist_1_joint");
79 std::vector<JointIndex> list_of_joints_to_keep_unlocked_by_id;
80 for(std::vector<std::string>::const_iterator it = list_of_joints_to_keep_unlocked_by_name.begin();
81 it != list_of_joints_to_keep_unlocked_by_name.end(); ++it)
85 list_of_joints_to_keep_unlocked_by_id.push_back(model.
getJointId(joint_name));
87 std::cout <<
"joint: " << joint_name <<
" does not belong to the model";
91 list_of_joints_to_lock_by_id.clear();
95 if(
is_in_vector(list_of_joints_to_keep_unlocked_by_name,joint_name))
99 list_of_joints_to_lock_by_id.push_back(
joint_id);
107 std::cout <<
"List of joints in the second reduced model:" << std::endl;
109 std::cout <<
"\t- " << reduced_model2.
names[
joint_id] << std::endl;
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
std::vector< std::string > names
Name of joint i
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
#define PINOCCHIO_MODEL_DIR
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
int main(int argc, char **argv)
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
Main pinocchio namespace.
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
bool is_in_vector(const std::vector< T > &vector, const T &elt)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
JointCollectionTpl & model
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::vector< JointIndex > list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model)
Build a reduced model from a given input model and a list of joint to lock.