Skip to content

Commit

Permalink
Use const reference for std::string
Browse files Browse the repository at this point in the history
  • Loading branch information
efernandez committed Apr 27, 2018
1 parent 94d45f5 commit 2938455
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ class NodeletLazy: public nodelet::Nodelet
*/
template<class T> ros::Publisher
advertise(ros::NodeHandle& nh,
std::string topic, int queue_size, bool latch=false)
const std::string& topic, int queue_size, bool latch=false)
{
boost::mutex::scoped_lock lock(connection_mutex_);
ros::SubscriberStatusCallback connect_cb
Expand Down

0 comments on commit 2938455

Please sign in to comment.