From: Walter Fetter Lages Date: Sat, 4 Feb 2023 21:47:28 +0000 (-0300) Subject: Change std::placeholders usage. X-Git-Url: http://git.ece.ufrgs.br/?a=commitdiff_plain;h=f65106a4b3fb946d2b7757984506e81ff6db517c;p=q2d.git Change std::placeholders usage. --- diff --git a/q2d_teleop/src/q2d_teleop_rviz.cpp b/q2d_teleop/src/q2d_teleop_rviz.cpp index aa79d84..265cf8f 100644 --- a/q2d_teleop/src/q2d_teleop_rviz.cpp +++ b/q2d_teleop/src/q2d_teleop_rviz.cpp @@ -56,14 +56,13 @@ class Q2dTeleop: public rclcpp::Node Q2dTeleop::Q2dTeleop(void): Node("Q2d_teleop_rviz"), q_(2) { - using std::placeholders::_1; - clickSub_=create_subscription("clicked_point",100,std::bind(&Q2dTeleop::clickCB,this,_1)); + clickSub_=create_subscription("clicked_point",100,std::bind(&Q2dTeleop::clickCB,this,std::placeholders::_1)); shoulderCmdPub_=create_publisher("shoulder_controller/command",100); elbowCmdPub_=create_publisher("elbow_controller/command",100); rclcpp::QoS qos(rclcpp::KeepLast(1)); qos.transient_local(); - auto robotDescriptionSubscriber_=create_subscription("robot_description",qos,std::bind(&Q2dTeleop::robotDescriptionCB,this,_1)); + auto robotDescriptionSubscriber_=create_subscription("robot_description",qos,std::bind(&Q2dTeleop::robotDescriptionCB,this,std::placeholders::_1)); while(robotDescription_.empty()) { RCLCPP_WARN_STREAM_SKIPFIRST_THROTTLE(get_logger(),*get_clock(),1000,"Waiting for robot model on /robot_description."); diff --git a/q2d_teleop/src/q2d_teleop_tablet.cpp b/q2d_teleop/src/q2d_teleop_tablet.cpp index ecd06b3..6b6385a 100644 --- a/q2d_teleop/src/q2d_teleop_tablet.cpp +++ b/q2d_teleop/src/q2d_teleop_tablet.cpp @@ -57,14 +57,13 @@ class Q2dTeleop: public rclcpp::Node Q2dTeleop::Q2dTeleop(void): Node("q2d_teleop_tablet"), q_(2) { - using std::placeholders::_1; - joySub_=create_subscription("joy",100,std::bind(&Q2dTeleop::joyCB,this,_1)); + joySub_=create_subscription("joy",100,std::bind(&Q2dTeleop::joyCB,this,std::placeholders::_1)); shoulderCmdPub_=create_publisher("shoulder_controller/command",100); elbowCmdPub_=create_publisher("elbow_controller/command",100); rclcpp::QoS qos(rclcpp::KeepLast(1)); qos.transient_local(); - auto robotDescriptionSubscriber_=create_subscription("robot_description",qos,std::bind(&Q2dTeleop::robotDescriptionCB,this,_1)); + auto robotDescriptionSubscriber_=create_subscription("robot_description",qos,std::bind(&Q2dTeleop::robotDescriptionCB,this,std::placeholders::_1)); while(robotDescription_.empty()) { RCLCPP_WARN_STREAM_SKIPFIRST_THROTTLE(get_logger(),*get_clock(),1000,"Waiting for robot model on /robot_description.");