diff --git a/src/darwin_arm_kinematics.cpp b/src/darwin_arm_kinematics.cpp index ee1bc2220a986f85f77eaf61ce312b22df6ce0ed..a3cd15f145974f0648532579a88ccd384cea6cd6 100644 --- a/src/darwin_arm_kinematics.cpp +++ b/src/darwin_arm_kinematics.cpp @@ -44,7 +44,7 @@ void CDarwinArmKinematics::load_chain(std::string &filename) if(stat(filename.c_str(),&buffer)==0) { try{ - std::auto_ptr<joints_t> chain(darwin_kin_chain(filename.c_str(), xml_schema::flags::dont_validate)); + std::unique_ptr<joints_t> chain(darwin_kin_chain(filename.c_str(), xml_schema::flags::dont_validate)); extra=6-chain->joint().size(); if(extra<0) extra=0; this->q_max.resize(6); diff --git a/src/darwin_leg_kinematics.cpp b/src/darwin_leg_kinematics.cpp index 8d0213506dca12da0e5fd41229ca30e7bdfc639c..c5107e355c85ab121aa4a7e5012cb9042f2924e5 100644 --- a/src/darwin_leg_kinematics.cpp +++ b/src/darwin_leg_kinematics.cpp @@ -97,7 +97,7 @@ void CDarwinLegKinematics::load_chain(std::string &filename) if(stat(filename.c_str(),&buffer)==0) { try{ - std::auto_ptr<joints_t> chain(darwin_kin_chain(filename.c_str(), xml_schema::flags::dont_validate)); + std::unique_ptr<joints_t> chain(darwin_kin_chain(filename.c_str(), xml_schema::flags::dont_validate)); this->fwd_kin_params.clear(); this->fwd_kin_transforms.clear(); this->num_dof=0;