Skip to content

Commit

Permalink
use lambda instead of bind (c++14)
Browse files Browse the repository at this point in the history
  • Loading branch information
finani committed Aug 8, 2024
1 parent c56239a commit 2f29b14
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 4 deletions.
3 changes: 2 additions & 1 deletion mvsim_node_src/mvsim_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ros::Subscriber>(n_.subscribe<Msg_Twist>(
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<Msg_Twist>(
vehVarName("cmd_vel", *veh), 10,
Expand Down
8 changes: 5 additions & 3 deletions mvsim_node_src/mvsim_node_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<mvsim::mvsimNodeConfig> dr_srv;
dynamic_reconfigure::Server<mvsim::mvsimNodeConfig>::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->
Expand Down

0 comments on commit 2f29b14

Please sign in to comment.