Skip to content

Commit 4aed1e3

Browse files
committed
cras_topic_tools: Little fixes suggested by linters.
1 parent a4caa4f commit 4aed1e3

File tree

7 files changed

+13
-6
lines changed

7 files changed

+13
-6
lines changed

cras_topic_tools/include/cras_topic_tools/priority_mux_base.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,8 @@ class PriorityMux : public ::cras::HasLogger
107107
const SetTimerFn& setTimerFn, const ::ros::Time& now, const ::cras::LogHelperPtr& log,
108108
const ::std::string& noneTopic = "__none", int nonePriority = 0);
109109

110+
virtual ~PriorityMux();
111+
110112
/**
111113
* \brief Callback function run when input topic message is received.
112114
*

cras_topic_tools/include/cras_topic_tools/repeat.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ class RepeatMessagesNodelet : public ::cras::Nodelet
111111
/**
112112
* \brief Reset the repeater, e.g. after a time jump.
113113
*/
114-
void reset();
114+
void reset() override;
115115

116116
/**
117117
* \brief Record the incoming message if it passes validations, and publish it if `publishOnlyOnTimer` is false.

cras_topic_tools/include/cras_topic_tools/throttle_messages.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,7 @@ class ThrottleMessagesNodelet : public ::cras::Nodelet
9595
/**
9696
* \brief Reset the rate limiter, e.g. after a time jump.
9797
*/
98-
void reset();
98+
void reset() override;
9999

100100
/**
101101
* \brief Publish the incoming message if the rate limiter allows.

cras_topic_tools/src/generic_lazy_pubsub.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,8 @@ cras::GenericLazyPubSub::GenericLazyPubSub(
3737
const size_t inQueueSize, const size_t outQueueSize, CallbackType callback,
3838
ros::SubscribeOptions subscribeOptions, const cras::LogHelperPtr& logHelper) :
3939
cras::ConditionalSubscriber(cras::bind_front(&cras::GenericLazyPubSub::subscribe, this), logHelper),
40-
topicIn(topicIn), topicOut(topicOut), callback(std::move(callback)), subscribeOptions(std::move(subscribeOptions)),
41-
inQueueSize(inQueueSize), outQueueSize(outQueueSize), nhIn(nhIn), nhOut(nhOut)
40+
topicIn(topicIn), topicOut(topicOut), inQueueSize(inQueueSize), outQueueSize(outQueueSize),
41+
nhIn(nhIn), nhOut(nhOut), callback(std::move(callback)), subscribeOptions(std::move(subscribeOptions))
4242
{
4343
// We have to connect at the beginning so that we can create the publisher from a subscribed message.
4444
std::lock_guard<std::mutex> lock(this->connectMutex);
@@ -105,7 +105,7 @@ ros::AdvertiseOptions cras::GenericLazyPubSub::createAdvertiseOptions(
105105
opts.has_header = cras::hasHeader(*msg);
106106
if (event.getConnectionHeaderPtr() != nullptr)
107107
{
108-
const auto header = event.getConnectionHeader();
108+
const auto& header = event.getConnectionHeader();
109109
opts.latch = header.find("latching") != header.end() && event.getConnectionHeader()["latching"] == "1";
110110
}
111111
return opts;

cras_topic_tools/src/priority_mux_base.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ PriorityMux::PriorityMux(const std::unordered_map<std::string, cras::priority_mu
2323
const cras::PriorityMux::SetTimerFn& setTimerFn, const ::ros::Time& now,
2424
const cras::LogHelperPtr& log, const std::string& noneTopic, int nonePriority) :
2525
cras::HasLogger(log), topicConfigs(topicConfigs), lockConfigs(lockConfigs), setTimer(setTimerFn),
26-
noneTopic(noneTopic), nonePriority(nonePriority)
26+
noneTopic(noneTopic), nonePriority(nonePriority), lastActivePriority(nonePriority)
2727
{
2828
this->resetImpl(now);
2929

@@ -40,6 +40,8 @@ PriorityMux::PriorityMux(const std::unordered_map<std::string, cras::priority_mu
4040
}
4141
}
4242

43+
PriorityMux::~PriorityMux() = default;
44+
4345
bool PriorityMux::cb(const std::string& inTopic, const ros::Time& stamp, const ros::Time& now)
4446
{
4547
const auto it = this->topicConfigs.find(inTopic);

cras_topic_tools/src/repeat.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,8 @@ void RepeatMessagesNodelet::onReset(const ros::MessageEvent<const topic_tools::S
105105

106106
void RepeatMessagesNodelet::reset()
107107
{
108+
NodeletWithSharedTfBuffer::reset();
109+
108110
this->timer.setPeriod(this->rate->expectedCycleTime(), true);
109111

110112
std::lock_guard<std::mutex> lock(this->msgMutex);

cras_topic_tools/src/throttle_messages.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,7 @@ void ThrottleMessagesNodelet::onReset(const ros::MessageEvent<const topic_tools:
110110

111111
void ThrottleMessagesNodelet::reset()
112112
{
113+
NodeletWithSharedTfBuffer::reset();
113114
std::lock_guard<std::mutex> lock(this->limiterMutex);
114115
this->limiter->reset();
115116
}

0 commit comments

Comments
 (0)