Minor optimizations of cases with no subscribers (#755)
parent
b274743eb7
commit
8dc0352d43
|
@ -186,10 +186,12 @@ void Node::PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event) {
|
|||
// frequency, and republishing it would be computationally wasteful.
|
||||
if (trajectory_state.local_slam_data->time !=
|
||||
extrapolator.GetLastPoseTime()) {
|
||||
// TODO(gaschler): Consider using other message without time information.
|
||||
if (scan_matched_point_cloud_publisher_.getNumSubscribers() > 0) {
|
||||
// TODO(gaschler): Consider using other message without time
|
||||
// information.
|
||||
carto::sensor::TimedPointCloud point_cloud;
|
||||
point_cloud.reserve(
|
||||
trajectory_state.local_slam_data->range_data_in_local.returns.size());
|
||||
point_cloud.reserve(trajectory_state.local_slam_data
|
||||
->range_data_in_local.returns.size());
|
||||
for (const Eigen::Vector3f point :
|
||||
trajectory_state.local_slam_data->range_data_in_local.returns) {
|
||||
Eigen::Vector4f point_time;
|
||||
|
@ -201,6 +203,7 @@ void Node::PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event) {
|
|||
node_options_.map_frame,
|
||||
carto::sensor::TransformTimedPointCloud(
|
||||
point_cloud, trajectory_state.local_to_map.cast<float>())));
|
||||
}
|
||||
extrapolator.AddPose(trajectory_state.local_slam_data->time,
|
||||
trajectory_state.local_slam_data->local_pose);
|
||||
}
|
||||
|
@ -257,8 +260,8 @@ void Node::PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event) {
|
|||
|
||||
void Node::PublishTrajectoryNodeList(
|
||||
const ::ros::WallTimerEvent& unused_timer_event) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
if (trajectory_node_list_publisher_.getNumSubscribers() > 0) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
trajectory_node_list_publisher_.publish(
|
||||
map_builder_bridge_.GetTrajectoryNodeList());
|
||||
}
|
||||
|
@ -266,8 +269,8 @@ void Node::PublishTrajectoryNodeList(
|
|||
|
||||
void Node::PublishLandmarkPosesList(
|
||||
const ::ros::WallTimerEvent& unused_timer_event) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
if (landmark_poses_list_publisher_.getNumSubscribers() > 0) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
landmark_poses_list_publisher_.publish(
|
||||
map_builder_bridge_.GetLandmarkPosesList());
|
||||
}
|
||||
|
@ -275,8 +278,8 @@ void Node::PublishLandmarkPosesList(
|
|||
|
||||
void Node::PublishConstraintList(
|
||||
const ::ros::WallTimerEvent& unused_timer_event) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
if (constraint_list_publisher_.getNumSubscribers() > 0) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
constraint_list_publisher_.publish(map_builder_bridge_.GetConstraintList());
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue