Skip to content

Commit 78d2cd4

Browse files
committed
drop deprecated use of boost _1, _2
The symbols have always been used through implicit includes from ros_comm, but ROS-O considers changing these includes right now because of excessive deprecation warnings building all of ROS. ros-o/ros_comm#3 (copyright updates are enforced by Shadow's CI)
1 parent af2f341 commit 78d2cd4

File tree

5 files changed

+11
-11
lines changed

5 files changed

+11
-11
lines changed

sr_hand/include/sr_hand/sr_subscriber.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/*
2-
* Copyright 2010 Shadow Robot Company Ltd.
2+
* Copyright 2010, 2024 Shadow Robot Company Ltd.
33
*
44
* This program is free software: you can redistribute it and/or modify it
55
* under the terms of the GNU General Public License as published by the Free
@@ -101,7 +101,7 @@ class SRSubscriber
101101
* @param msg the target in radians
102102
* @param joint_name name of the joint we're sending the command to
103103
*/
104-
void cmd_callback(const std_msgs::Float64ConstPtr &msg, std::string &joint_name);
104+
void cmd_callback(const std_msgs::Float64ConstPtr &msg, const std::string &joint_name);
105105

106106
/// The vector of subscribers to the different joint topics.
107107
std::vector<Subscriber> controllers_sub;

sr_hand/src/sr_subscriber.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/*
2-
* Copyright 2010 Shadow Robot Company Ltd.
2+
* Copyright 2010, 2024 Shadow Robot Company Ltd.
33
*
44
* This program is free software: you can redistribute it and/or modify it
55
* under the terms of the GNU General Public License as published by the Free
@@ -81,9 +81,10 @@ namespace shadowrobot
8181
for (SRArticulatedRobot::JointsMap::iterator joint = sr_articulated_robot->joints_map.begin();
8282
joint != sr_articulated_robot->joints_map.end(); ++joint)
8383
{
84+
std::string joint_name{ joint->first };
8485
controllers_sub.push_back(node.subscribe<std_msgs::Float64>(
8586
"sh_" + boost::to_lower_copy(joint->first + "_position_controller/command"), 2,
86-
boost::bind(&SRSubscriber::cmd_callback, this, _1, joint->first)));
87+
[this,joint_name](auto msg) { cmd_callback(msg, joint_name); }));
8788
}
8889
}
8990

@@ -110,7 +111,7 @@ namespace shadowrobot
110111
}
111112
}
112113

113-
void SRSubscriber::cmd_callback(const std_msgs::Float64ConstPtr &msg, std::string &joint_name)
114+
void SRSubscriber::cmd_callback(const std_msgs::Float64ConstPtr &msg, const std::string &joint_name)
114115
{
115116
// converting to degrees as the old can interface was expecting degrees
116117
sr_articulated_robot->sendupdate(joint_name, sr_math_utils::to_degrees(msg->data));

sr_mechanism_controllers/src/joint_spline_trajectory_action_controller.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/*
2-
* Copyright 2011 Shadow Robot Company Ltd.
2+
* Copyright 2011, 2024 Shadow Robot Company Ltd.
33
*
44
* This program is free software: you can redistribute it and/or modify it
55
* under the terms of the GNU General Public License as published by the Free
@@ -140,8 +140,7 @@ namespace shadowrobot
140140
nh_tilde("~"), use_sendupdate(false)
141141
{
142142
action_server = boost::shared_ptr<JTAS>(new JTAS("/r_arm_controller/joint_trajectory_action",
143-
boost::bind(&JointTrajectoryActionController::execute_trajectory,
144-
this, _1),
143+
[this](auto msg){ execute_trajectory(msg); },
145144
false));
146145
std::vector<std::string> joint_labels;
147146

sr_mechanism_controllers/src/joint_trajectory_action_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/*
2-
* Copyright 2011 Shadow Robot Company Ltd.
2+
* Copyright 2011, 2024 Shadow Robot Company Ltd.
33
*
44
* This program is free software: you can redistribute it and/or modify it
55
* under the terms of the GNU General Public License as published by the Free
@@ -38,7 +38,7 @@ namespace shadowrobot
3838
{
3939
action_server = boost::shared_ptr<JTAS>(
4040
new JTAS("/r_arm_controller/joint_trajectory_action",
41-
boost::bind(&JointTrajectoryActionController::execute_trajectory, this, _1),
41+
[this](auto msg){ execute_trajectory(msg); },
4242
false));
4343

4444
// Create a map of joint names to their command publishers

sr_tactile_sensors/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
<!--
2-
Copyright 2022 Shadow Robot Company Ltd.
2+
Copyright 2022, 2024 Shadow Robot Company Ltd.
33
This program is free software: you can redistribute it and/or modify it
44
under the terms of the GNU General Public License as published by the Free
55
Software Foundation version 2 of the License.

0 commit comments

Comments
 (0)