Change std::placeholders usage.
authorWalter Fetter Lages <w.fetter@ieee.org>
Sat, 4 Feb 2023 21:47:28 +0000 (18:47 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Sat, 4 Feb 2023 21:47:28 +0000 (18:47 -0300)
q2d_teleop/src/q2d_teleop_rviz.cpp
q2d_teleop/src/q2d_teleop_tablet.cpp

index aa79d84..265cf8f 100644 (file)
@@ -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<geometry_msgs::msg::PointStamped>("clicked_point",100,std::bind(&Q2dTeleop::clickCB,this,_1));
+       clickSub_=create_subscription<geometry_msgs::msg::PointStamped>("clicked_point",100,std::bind(&Q2dTeleop::clickCB,this,std::placeholders::_1));
        shoulderCmdPub_=create_publisher<std_msgs::msg::Float64>("shoulder_controller/command",100);
         elbowCmdPub_=create_publisher<std_msgs::msg::Float64>("elbow_controller/command",100);
        
         rclcpp::QoS qos(rclcpp::KeepLast(1));
         qos.transient_local();
-        auto robotDescriptionSubscriber_=create_subscription<std_msgs::msg::String>("robot_description",qos,std::bind(&Q2dTeleop::robotDescriptionCB,this,_1));
+        auto robotDescriptionSubscriber_=create_subscription<std_msgs::msg::String>("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.");
index ecd06b3..6b6385a 100644 (file)
@@ -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<sensor_msgs::msg::Joy>("joy",100,std::bind(&Q2dTeleop::joyCB,this,_1));
+       joySub_=create_subscription<sensor_msgs::msg::Joy>("joy",100,std::bind(&Q2dTeleop::joyCB,this,std::placeholders::_1));
        shoulderCmdPub_=create_publisher<std_msgs::msg::Float64>("shoulder_controller/command",100);
         elbowCmdPub_=create_publisher<std_msgs::msg::Float64>("elbow_controller/command",100);
        
         rclcpp::QoS qos(rclcpp::KeepLast(1));
         qos.transient_local();
-        auto robotDescriptionSubscriber_=create_subscription<std_msgs::msg::String>("robot_description",qos,std::bind(&Q2dTeleop::robotDescriptionCB,this,_1));
+        auto robotDescriptionSubscriber_=create_subscription<std_msgs::msg::String>("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.");