modify rviz presentation

This commit is contained in:
Joanna-HE
2024-05-20 04:53:15 -04:00
parent adf3a6ffbd
commit d6dd493d94
2 changed files with 13 additions and 14 deletions

View File

@@ -17,7 +17,7 @@ Panels:
- /Odometry1/Odometry1/Covariance1/Orientation1 - /Odometry1/Odometry1/Covariance1/Orientation1
- /MarkerArray1/Namespaces1 - /MarkerArray1/Namespaces1
Splitter Ratio: 0.6432291865348816 Splitter Ratio: 0.6432291865348816
Tree Height: 777 Tree Height: 1297
- Class: rviz/Selection - Class: rviz/Selection
Name: Selection Name: Selection
- Class: rviz/Tool Properties - Class: rviz/Tool Properties
@@ -33,7 +33,6 @@ Panels:
Name: Views Name: Views
Splitter Ratio: 0.5 Splitter Ratio: 0.5
- Class: rviz/Time - Class: rviz/Time
Experimental: false
Name: Time Name: Time
SyncMode: 0 SyncMode: 0
SyncSource: surround SyncSource: surround
@@ -68,7 +67,7 @@ Visualization Manager:
Length: 0.699999988079071 Length: 0.699999988079071
Name: Axes Name: Axes
Radius: 0.05999999865889549 Radius: 0.05999999865889549
Reference Frame: aft_mapped Reference Frame: body
Show Trail: false Show Trail: false
Value: true Value: true
- Class: rviz/Group - Class: rviz/Group
@@ -347,11 +346,11 @@ Visualization Manager:
Saved: ~ Saved: ~
Window Geometry: Window Geometry:
Displays: Displays:
collapsed: true collapsed: false
Height: 1016 Height: 1536
Hide Left Dock: true Hide Left Dock: false
Hide Right Dock: true Hide Right Dock: true
QMainWindow State: 000000ff00000000fd0000000400000000000001c800000346fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d00000346000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073800000052fc0100000002fb0000000800540069006d0065010000000000000738000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000007380000034600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 QMainWindow State: 000000ff00000000fd0000000400000000000001c80000054efc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000054e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b800000052fc0100000002fb0000000800540069006d00650100000000000009b8000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000007ea0000054e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection: Selection:
collapsed: false collapsed: false
Time: Time:
@@ -360,6 +359,6 @@ Window Geometry:
collapsed: false collapsed: false
Views: Views:
collapsed: true collapsed: true
Width: 1848 Width: 2488
X: 72 X: 72
Y: 27 Y: 27

View File

@@ -271,7 +271,7 @@ void set_posestamp(T & out)
void publish_odometry(const ros::Publisher & pubOdomAftMapped) void publish_odometry(const ros::Publisher & pubOdomAftMapped)
{ {
odomAftMapped.header.frame_id = "camera_init"; odomAftMapped.header.frame_id = "camera_init";
odomAftMapped.child_frame_id = "aft_mapped"; odomAftMapped.child_frame_id = "body";
if (publish_odometry_without_downsample) if (publish_odometry_without_downsample)
{ {
odomAftMapped.header.stamp = ros::Time().fromSec(time_current); odomAftMapped.header.stamp = ros::Time().fromSec(time_current);
@@ -295,7 +295,7 @@ void publish_odometry(const ros::Publisher & pubOdomAftMapped)
q.setY(odomAftMapped.pose.pose.orientation.y); q.setY(odomAftMapped.pose.pose.orientation.y);
q.setZ(odomAftMapped.pose.pose.orientation.z); q.setZ(odomAftMapped.pose.pose.orientation.z);
transform.setRotation( q ); transform.setRotation( q );
br.sendTransform( tf::StampedTransform( transform, odomAftMapped.header.stamp, "camera_init", "aft_mapped" ) ); br.sendTransform( tf::StampedTransform( transform, odomAftMapped.header.stamp, "camera_init", "body") );
} }
void publish_path(const ros::Publisher pubPath) void publish_path(const ros::Publisher pubPath)
@@ -380,16 +380,16 @@ int main(int argc, char** argv)
("/cloud_registered", 1000); ("/cloud_registered", 1000);
ros::Publisher pubLaserCloudFullRes_body = nh.advertise<sensor_msgs::PointCloud2> ros::Publisher pubLaserCloudFullRes_body = nh.advertise<sensor_msgs::PointCloud2>
("/cloud_registered_body", 1000); ("/cloud_registered_body", 1000);
ros::Publisher pubLaserCloudEffect = nh.advertise<sensor_msgs::PointCloud2> // ros::Publisher pubLaserCloudEffect = nh.advertise<sensor_msgs::PointCloud2>
("/cloud_effected", 1000); // ("/cloud_effected", 1000);
ros::Publisher pubLaserCloudMap = nh.advertise<sensor_msgs::PointCloud2> ros::Publisher pubLaserCloudMap = nh.advertise<sensor_msgs::PointCloud2>
("/Laser_map", 1000); ("/Laser_map", 1000);
ros::Publisher pubOdomAftMapped = nh.advertise<nav_msgs::Odometry> ros::Publisher pubOdomAftMapped = nh.advertise<nav_msgs::Odometry>
("/aft_mapped_to_init", 1000); ("/aft_mapped_to_init", 1000);
ros::Publisher pubPath = nh.advertise<nav_msgs::Path> ros::Publisher pubPath = nh.advertise<nav_msgs::Path>
("/path", 1000); ("/path", 1000);
ros::Publisher plane_pub = nh.advertise<visualization_msgs::Marker> // ros::Publisher plane_pub = nh.advertise<visualization_msgs::Marker>
("/planner_normal", 1000); // ("/planner_normal", 1000);
//------------------------------------------------------------------------------------------------------ //------------------------------------------------------------------------------------------------------
signal(SIGINT, SigHandle); signal(SIGINT, SigHandle);
ros::Rate loop_rate(500); ros::Rate loop_rate(500);