Change std::placeholders usage. humble
authorWalter Fetter Lages <w.fetter@ieee.org>
Fri, 3 Feb 2023 04:30:10 +0000 (01:30 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Fri, 3 Feb 2023 04:30:10 +0000 (01:30 -0300)
src/computed_torque_controller.cpp

index 067d124..b02be6d 100644 (file)
@@ -81,9 +81,8 @@ namespace effort_controllers
 
                nJoints_=jointNames_.size();            
 
-               using std::placeholders::_1;
                sub_command_=get_node()->create_subscription<trajectory_msgs::msg::JointTrajectoryPoint>("command",1,
-                       std::bind(&ComputedTorqueController::commandCB,this,_1));
+                       std::bind(&ComputedTorqueController::commandCB,this,std::placeholders::_1));
 
                while(robotDescription_.empty())
                        RCLCPP_WARN_SKIPFIRST_THROTTLE(get_node()->get_logger(),*get_node()->get_clock(),1000,"Waiting for robot model on /robot_description.");