Fix typo. melodic
authorWalter Fetter Lages <w.fetter@ieee.org>
Wed, 12 Dec 2018 14:16:55 +0000 (12:16 -0200)
committerWalter Fetter Lages <w.fetter@ieee.org>
Wed, 12 Dec 2018 14:16:55 +0000 (12:16 -0200)
include/pid_plus_gravity_controller/pid_plus_gravity_controller.h
src/pid_plus_gravity_controller.cpp

index a7bac23..1732cea 100644 (file)
@@ -51,8 +51,8 @@ namespace effort_controllers
 
                ros::Subscriber sub_command_;
 
-               KDL::Tree tree;
-               KDL::Chain chain;
+               KDL::Tree tree_;
+               KDL::Chain chain_;
                KDL::ChainDynParam *chainParam_;
                                
                KDL::JntArray q_;
index d522e2e..1748753 100644 (file)
@@ -80,7 +80,7 @@ namespace effort_controllers
                        return false;
                }
                
-               if (!kdl_parser::treeFromString(robot_desc_string,tree))
+               if (!kdl_parser::treeFromString(robot_desc_string,tree_))
                {
                        ROS_ERROR("Failed to construct KDL tree.");
                        return false;
@@ -100,7 +100,7 @@ namespace effort_controllers
                        return false;
                }
                
-               if (!tree.getChain(chainRoot,chainTip,chain)) 
+               if (!tree_.getChain(chainRoot,chainTip,chain_)) 
                {
                        ROS_ERROR("Failed to get chain from KDL tree.");
                        return false;
@@ -111,15 +111,15 @@ namespace effort_controllers
                node_.param("gravity/y",g[1],0.0);
                node_.param("gravity/z",g[2],-9.8);
                
-               if((chainParam_=new KDL::ChainDynParam(chain,g)) == NULL)
+               if((chainParam_=new KDL::ChainDynParam(chain_,g)) == NULL)
                {
                        ROS_ERROR("Failed to create ChainDynParam.");
                        return false;
                }
 
-               q_.resize(chain.getNrOfJoints());
-               qr_.resize(chain.getNrOfJoints());
-               gravity_.resize(chain.getNrOfJoints());
+               q_.resize(chain_.getNrOfJoints());
+               qr_.resize(chain_.getNrOfJoints());
+               gravity_.resize(chain_.getNrOfJoints());
                
                return true;
        }