From 2f29b14d8e407ba54ad143efe64e91a11acbbf06 Mon Sep 17 00:00:00 2001 From: finani <10ezenfinani@gmail.com> Date: Wed, 7 Aug 2024 16:55:09 +0900 Subject: [PATCH] use lambda instead of bind (c++14) --- mvsim_node_src/mvsim_node.cpp | 3 ++- mvsim_node_src/mvsim_node_main.cpp | 8 +++++--- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/mvsim_node_src/mvsim_node.cpp b/mvsim_node_src/mvsim_node.cpp index 80b347ce..d810e4c1 100644 --- a/mvsim_node_src/mvsim_node.cpp +++ b/mvsim_node_src/mvsim_node.cpp @@ -603,7 +603,8 @@ void MVSimNode::initPubSubs(TPubSubPerVehicle& pubsubs, mvsim::VehicleBase* veh) #if PACKAGE_ROS_VERSION == 1 pubsubs.sub_cmd_vel = mvsim_node::make_shared(n_.subscribe( vehVarName("cmd_vel", *veh), 10, - boost::bind(&MVSimNode::onROSMsgCmdVel, this, _1, veh))); + [this, veh](Msg_Twist_CSPtr msg) + { return this->onROSMsgCmdVel(msg, veh); })); #else pubsubs.sub_cmd_vel = n_->create_subscription( vehVarName("cmd_vel", *veh), 10, diff --git a/mvsim_node_src/mvsim_node_main.cpp b/mvsim_node_src/mvsim_node_main.cpp index 1108d9ba..4567dd91 100644 --- a/mvsim_node_src/mvsim_node_main.cpp +++ b/mvsim_node_src/mvsim_node_main.cpp @@ -68,9 +68,11 @@ int main(int argc, char** argv) // Do this before parameter server, else some of the parameter server // values can be overwritten. dynamic_reconfigure::Server dr_srv; - dynamic_reconfigure::Server::CallbackType cb; - cb = boost::bind(&MVSimNode::configCallback, node.get(), _1, _2); - dr_srv.setCallback(cb); + dr_srv.setCallback( + [&node](mvsim::mvsimNodeConfig& config, uint32_t level) + { + return node->configCallback(config, level); + }); #endif // Tell ROS how fast to run this node->