Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Check publisher's conection #12

Merged
merged 2 commits into from
Jun 26, 2023
Merged
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
27 changes: 27 additions & 0 deletions src/plugin/BodyROSItem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -369,6 +369,9 @@ void BodyROSItem::updateForceSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
geometry_msgs::WrenchStamped force;
force.header.stamp.fromSec(io->currentTime());
force.header.frame_id = sensor->name();
Expand All @@ -388,6 +391,9 @@ void BodyROSItem::updateRateGyroSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::Imu gyro;
gyro.header.stamp.fromSec(io->currentTime());
gyro.header.frame_id = sensor->name();
Expand All @@ -404,6 +410,9 @@ void BodyROSItem::updateAccelSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::Imu accel;
accel.header.stamp.fromSec(io->currentTime());
accel.header.frame_id = sensor->name();
Expand All @@ -420,6 +429,9 @@ void BodyROSItem::updateImu
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::Imu imu;
imu.header.stamp.fromSec(io->currentTime());
imu.header.frame_id = sensor->name();
Expand All @@ -439,6 +451,9 @@ void BodyROSItem::updateVisionSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::Image vision;
vision.header.stamp.fromSec(io->currentTime());
vision.header.frame_id = sensor->name();
Expand All @@ -465,6 +480,9 @@ void BodyROSItem::updateRangeVisionSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::PointCloud2 range;
range.header.stamp.fromSec(io->currentTime());
range.header.frame_id = sensor->name();
Expand Down Expand Up @@ -539,6 +557,9 @@ void BodyROSItem::updateRangeSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::LaserScan range;
range.header.stamp.fromSec(io->currentTime());
range.header.frame_id = sensor->name();
Expand Down Expand Up @@ -571,6 +592,9 @@ void BodyROSItem::update3DRangeSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::PointCloud2 range;
// Header Info
range.header.stamp.fromSec(io->currentTime());
Expand Down Expand Up @@ -645,6 +669,9 @@ void BodyROSItem::update3DRangeSensor
if(!sensor->on()){
return;
}
if(publisher.getNumSubscribers() == 0){
return;
}
sensor_msgs::PointCloud range;
// Header Info
range.header.stamp.fromSec(io->currentTime());
Expand Down