fix scan_publish and pcd_save problem
parent
5354c5acba
commit
c98ff91705
|
@ -35,7 +35,7 @@ Panels:
|
||||||
Experimental: false
|
Experimental: false
|
||||||
Name: Time
|
Name: Time
|
||||||
SyncMode: 0
|
SyncMode: 0
|
||||||
SyncSource: currPoints
|
SyncSource: ""
|
||||||
Preferences:
|
Preferences:
|
||||||
PromptSaveOnExit: true
|
PromptSaveOnExit: true
|
||||||
Toolbars:
|
Toolbars:
|
||||||
|
@ -87,7 +87,7 @@ Visualization Manager:
|
||||||
Max Color: 255; 255; 255
|
Max Color: 255; 255; 255
|
||||||
Max Intensity: 150
|
Max Intensity: 150
|
||||||
Min Color: 0; 0; 0
|
Min Color: 0; 0; 0
|
||||||
Min Intensity: 1
|
Min Intensity: 0
|
||||||
Name: surround
|
Name: surround
|
||||||
Position Transformer: XYZ
|
Position Transformer: XYZ
|
||||||
Queue Size: 1
|
Queue Size: 1
|
||||||
|
@ -211,7 +211,7 @@ Visualization Manager:
|
||||||
Buffer Length: 2
|
Buffer Length: 2
|
||||||
Class: rviz/Path
|
Class: rviz/Path
|
||||||
Color: 25; 255; 255
|
Color: 25; 255; 255
|
||||||
Enabled: false
|
Enabled: true
|
||||||
Head Diameter: 0
|
Head Diameter: 0
|
||||||
Head Length: 0
|
Head Length: 0
|
||||||
Length: 0.30000001192092896
|
Length: 0.30000001192092896
|
||||||
|
@ -229,7 +229,7 @@ Visualization Manager:
|
||||||
Shaft Length: 0.4000000059604645
|
Shaft Length: 0.4000000059604645
|
||||||
Topic: /path
|
Topic: /path
|
||||||
Unreliable: false
|
Unreliable: false
|
||||||
Value: false
|
Value: true
|
||||||
- Alpha: 1
|
- Alpha: 1
|
||||||
Autocompute Intensity Bounds: false
|
Autocompute Intensity Bounds: false
|
||||||
Autocompute Value Bounds:
|
Autocompute Value Bounds:
|
||||||
|
@ -326,25 +326,25 @@ Visualization Manager:
|
||||||
Views:
|
Views:
|
||||||
Current:
|
Current:
|
||||||
Class: rviz/ThirdPersonFollower
|
Class: rviz/ThirdPersonFollower
|
||||||
Distance: 10
|
Distance: 62.12976837158203
|
||||||
Enable Stereo Rendering:
|
Enable Stereo Rendering:
|
||||||
Stereo Eye Separation: 0.05999999865889549
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
Stereo Focal Distance: 1
|
Stereo Focal Distance: 1
|
||||||
Swap Stereo Eyes: false
|
Swap Stereo Eyes: false
|
||||||
Value: false
|
Value: false
|
||||||
Focal Point:
|
Focal Point:
|
||||||
X: 5.284592628479004
|
X: 5.488441467285156
|
||||||
Y: -1.0116491317749023
|
Y: -29.57037353515625
|
||||||
Z: -9.5367431640625e-7
|
Z: 2.2303884179564193e-6
|
||||||
Focal Shape Fixed Size: false
|
Focal Shape Fixed Size: false
|
||||||
Focal Shape Size: 0.05000000074505806
|
Focal Shape Size: 0.05000000074505806
|
||||||
Invert Z Axis: true
|
Invert Z Axis: false
|
||||||
Name: Current View
|
Name: Current View
|
||||||
Near Clip Distance: 0.009999999776482582
|
Near Clip Distance: 0.009999999776482582
|
||||||
Pitch: -0.31460127234458923
|
Pitch: 0.740202784538269
|
||||||
Target Frame: camera_init
|
Target Frame: camera_init
|
||||||
Value: ThirdPersonFollower (rviz)
|
Value: ThirdPersonFollower (rviz)
|
||||||
Yaw: 4.585422039031982
|
Yaw: 3.57222843170166
|
||||||
Saved: ~
|
Saved: ~
|
||||||
Window Geometry:
|
Window Geometry:
|
||||||
Displays:
|
Displays:
|
||||||
|
|
|
@ -445,20 +445,20 @@ PointCloudXYZI::Ptr pcl_wait_pub(new PointCloudXYZI(500000, 1));
|
||||||
PointCloudXYZI::Ptr pcl_wait_save(new PointCloudXYZI());
|
PointCloudXYZI::Ptr pcl_wait_save(new PointCloudXYZI());
|
||||||
void publish_frame_world(const ros::Publisher & pubLaserCloudFullRes)
|
void publish_frame_world(const ros::Publisher & pubLaserCloudFullRes)
|
||||||
{
|
{
|
||||||
PointCloudXYZI::Ptr laserCloudFullRes(dense_pub_en ? feats_undistort : feats_down_body);
|
|
||||||
int size = laserCloudFullRes->points.size();
|
|
||||||
PointCloudXYZI::Ptr laserCloudWorld( \
|
|
||||||
new PointCloudXYZI(size, 1));
|
|
||||||
|
|
||||||
for (int i = 0; i < size; i++)
|
|
||||||
{
|
|
||||||
RGBpointBodyToWorld(&laserCloudFullRes->points[i], \
|
|
||||||
&laserCloudWorld->points[i]);
|
|
||||||
}
|
|
||||||
|
|
||||||
// *pcl_wait_pub += *laserCloudWorld;
|
// *pcl_wait_pub += *laserCloudWorld;
|
||||||
if(1)
|
if(scan_pub_en)
|
||||||
{
|
{
|
||||||
|
PointCloudXYZI::Ptr laserCloudFullRes(dense_pub_en ? feats_undistort : feats_down_body);
|
||||||
|
int size = laserCloudFullRes->points.size();
|
||||||
|
PointCloudXYZI::Ptr laserCloudWorld( \
|
||||||
|
new PointCloudXYZI(size, 1));
|
||||||
|
|
||||||
|
for (int i = 0; i < size; i++)
|
||||||
|
{
|
||||||
|
RGBpointBodyToWorld(&laserCloudFullRes->points[i], \
|
||||||
|
&laserCloudWorld->points[i]);
|
||||||
|
}
|
||||||
|
|
||||||
sensor_msgs::PointCloud2 laserCloudmsg;
|
sensor_msgs::PointCloud2 laserCloudmsg;
|
||||||
pcl::toROSMsg(*laserCloudWorld, laserCloudmsg);
|
pcl::toROSMsg(*laserCloudWorld, laserCloudmsg);
|
||||||
laserCloudmsg.header.stamp = ros::Time::now();
|
laserCloudmsg.header.stamp = ros::Time::now();
|
||||||
|
@ -471,8 +471,17 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFullRes)
|
||||||
/**************** save map ****************/
|
/**************** save map ****************/
|
||||||
/* 1. make sure you have enough memories
|
/* 1. make sure you have enough memories
|
||||||
/* 2. pcd save will largely influence the real-time performences **/
|
/* 2. pcd save will largely influence the real-time performences **/
|
||||||
if (laserCloudWorld->size() > 0 && pcd_save_en)
|
if (pcd_save_en)
|
||||||
{
|
{
|
||||||
|
int size = feats_undistort->points.size();
|
||||||
|
PointCloudXYZI::Ptr laserCloudWorld( \
|
||||||
|
new PointCloudXYZI(size, 1));
|
||||||
|
|
||||||
|
for (int i = 0; i < size; i++)
|
||||||
|
{
|
||||||
|
RGBpointBodyToWorld(&feats_undistort->points[i], \
|
||||||
|
&laserCloudWorld->points[i]);
|
||||||
|
}
|
||||||
*pcl_wait_save += *laserCloudWorld;
|
*pcl_wait_save += *laserCloudWorld;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -879,7 +888,7 @@ int main(int argc, char** argv)
|
||||||
|
|
||||||
/******* Publish points *******/
|
/******* Publish points *******/
|
||||||
publish_path(pubPath);
|
publish_path(pubPath);
|
||||||
if(scan_pub_en) publish_frame_world(pubLaserCloudFullRes);
|
if (scan_pub_en || pcd_save_en) publish_frame_world(pubLaserCloudFullRes);
|
||||||
|
|
||||||
// publish_effect_world(pubLaserCloudEffect);
|
// publish_effect_world(pubLaserCloudEffect);
|
||||||
// publish_map(pubLaserCloudMap);
|
// publish_map(pubLaserCloudMap);
|
||||||
|
|
Loading…
Reference in New Issue