Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -282,6 +282,7 @@ int main(int argc, char * argv[]) {
ros::Time start_scan_time;
ros::Time end_scan_time;
double scan_duration;
uint32_t prev_num_subscribers=(uint32_t)-1;
while (ros::ok()) {
rplidar_response_measurement_node_hq_t nodes[360*8];
size_t count = _countof(nodes);
Expand Down Expand Up @@ -349,6 +350,18 @@ int main(int argc, char * argv[]) {
}
}

uint32_t num_subcribers = scan_pub.getNumSubscribers();
if (num_subcribers == 0 && prev_num_subscribers != 0) {
ROS_DEBUG("No subscribers: Stop motor");
drv->stop();
drv->stopMotor();
} else if (num_subcribers != 0 && prev_num_subscribers == 0) {
ROS_DEBUG("At least one subscribers: Start motor");
drv->startMotor();
drv->startScan(0,1);
}
prev_num_subscribers = num_subcribers;

ros::spinOnce();
}

Expand Down