From cac6a41f7609a6ec0fa7f135f317729c136affd7 Mon Sep 17 00:00:00 2001 From: ssnover95 Date: Wed, 31 Oct 2018 12:43:43 -0400 Subject: [PATCH] Reduce scope of joint and mark type as auto. Mark type of robot_model as auto. --- baxter_sim_kinematics/src/arm_kinematics.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/baxter_sim_kinematics/src/arm_kinematics.cpp b/baxter_sim_kinematics/src/arm_kinematics.cpp index 24d7b0d..98eee86 100644 --- a/baxter_sim_kinematics/src/arm_kinematics.cpp +++ b/baxter_sim_kinematics/src/arm_kinematics.cpp @@ -245,14 +245,13 @@ bool Kinematics::loadModel(const std::string xml) { */ bool Kinematics::readJoints(urdf::Model &robot_model) { num_joints = 0; - boost::shared_ptr link = robot_model.getLink(tip_name); - boost::shared_ptr joint; + auto link = robot_model.getLink(tip_name); for (int i = 0; i < chain.getNrOfSegments(); i++) while (link && link->name != root_name) { if (!(link->parent_joint)) { break; } - joint = robot_model.getJoint(link->parent_joint->name); + auto joint = robot_model.getJoint(link->parent_joint->name); if (!joint) { ROS_ERROR("Could not find joint: %s", link->parent_joint->name.c_str()); return false; @@ -272,7 +271,7 @@ bool Kinematics::readJoints(urdf::Model &robot_model) { link = robot_model.getLink(tip_name); unsigned int i = 0; while (link && i < num_joints) { - joint = robot_model.getJoint(link->parent_joint->name); + auto joint = robot_model.getJoint(link->parent_joint->name); if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) { ROS_INFO("getting bounds for joint: [%s]", joint->name.c_str());