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

use private handler #56

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
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
20 changes: 15 additions & 5 deletions launch/mapping_horizon.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,28 @@
<launch>

<arg name="rviz" default="true" />
<arg name="cloud" default="/livox/lidar"/>

<node pkg="livox_mapping" type="loam_scanRegistration_horizon" name="scanRegistration_horizon" output="screen">
<remap from="~input" to="$(arg cloud)"/>
<remap from="~cloud" to="/livox_cloud"/>
<remap from="~cloud_sharp" to="/laser_cloud_sharp"/>
<remap from="~cloud_flat" to="/laser_cloud_flat"/>
</node>

<node pkg="livox_mapping" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.2" />
<param name="filter_parameter_surf" type="double" value="0.4" />
<remap from="~cloud" to="/livox_cloud"/>
<remap from="~cloud_sharp" to="/laser_cloud_sharp"/>
<remap from="~cloud_flat" to="/laser_cloud_flat"/>
<remap from="~cloud_surround" to="/laser_surround"/>
<remap from="~cloud_surround_corner" to="/laser_surround_corner"/>
<remap from="~odometry" to="/aft_mapped_to_init"/>
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.2" />
<param name="filter_parameter_surf" type="double" value="0.4" />
</node>

<node pkg="livox_mapping" type="livox_repub" name="livox_repub" output="screen" >
<remap from="/livox/lidar" to="/livox/lidar" />
<remap from="$(arg cloud)" to="$(arg cloud)" />
</node>

<group if="$(arg rviz)">
Expand Down
18 changes: 14 additions & 4 deletions launch/mapping_mid.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,24 @@
<launch>

<arg name="rviz" default="true" />
<arg name="cloud" default="/livox/lidar"/>

<node pkg="livox_mapping" type="loam_scanRegistration" name="scanRegistration" output="screen">
<remap from="~input" to="$(arg cloud)"/>
<remap from="~cloud" to="/livox_cloud"/>
<remap from="~cloud_sharp" to="/laser_cloud_sharp"/>
<remap from="~cloud_flat" to="/laser_cloud_flat"/>
</node>

<node pkg="livox_mapping" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.1" />
<param name="filter_parameter_surf" type="double" value="0.2" />
<remap from="~cloud" to="/livox_cloud"/>
<remap from="~cloud_sharp" to="/laser_cloud_sharp"/>
<remap from="~cloud_flat" to="/laser_cloud_flat"/>
<remap from="~cloud_surround" to="/laser_surround"/>
<remap from="~cloud_surround_corner" to="/laser_surround_corner"/>
<remap from="~odometry" to="/aft_mapped_to_init"/>
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.1" />
<param name="filter_parameter_surf" type="double" value="0.2" />
</node>

<group if="$(arg rviz)">
Expand Down
17 changes: 14 additions & 3 deletions launch/mapping_outdoor.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,25 @@
<launch>

<arg name="rviz" default="true" />
<arg name="cloud" default="/livox/lidar"/>

<node pkg="livox_mapping" type="loam_scanRegistration" name="scanRegistration" output="screen">
<remap from="~input" to="$(arg cloud)"/>
<remap from="~cloud" to="/livox_cloud"/>
<remap from="~cloud_sharp" to="/laser_cloud_sharp"/>
<remap from="~cloud_flat" to="/laser_cloud_flat"/>
</node>

<node pkg="livox_mapping" type="loam_laserMapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.2" />
<param name="filter_parameter_surf" type="double" value="0.4" />
<remap from="~cloud" to="/livox_cloud"/>
<remap from="~cloud_sharp" to="/laser_cloud_sharp"/>
<remap from="~cloud_flat" to="/laser_cloud_flat"/>
<remap from="~cloud_surround" to="/laser_surround"/>
<remap from="~cloud_surround_corner" to="/laser_surround_corner"/>
<remap from="~odometry" to="/aft_mapped_to_init"/>
<param name="map_file_path" type="string" value=" " />
<param name="filter_parameter_corner" type="double" value="0.2" />
<param name="filter_parameter_surf" type="double" value="0.4" />
</node>

<group if="$(arg rviz)">
Expand Down
14 changes: 7 additions & 7 deletions src/laserMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -381,26 +381,26 @@ void laserCloudFullResHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloud
int main(int argc, char** argv)
{
ros::init(argc, argv, "laserMapping");
ros::NodeHandle nh;
ros::NodeHandle nh("~");

ros::Subscriber subLaserCloudCornerLast = nh.subscribe<sensor_msgs::PointCloud2>
("/laser_cloud_sharp", 100, laserCloudCornerLastHandler);
("cloud_sharp", 100, laserCloudCornerLastHandler);

ros::Subscriber subLaserCloudSurfLast = nh.subscribe<sensor_msgs::PointCloud2>
("/laser_cloud_flat", 100, laserCloudSurfLastHandler);
("cloud_flat", 100, laserCloudSurfLastHandler);

ros::Subscriber subLaserCloudFullRes = nh.subscribe<sensor_msgs::PointCloud2>
("/livox_cloud", 100, laserCloudFullResHandler);
("cloud", 100, laserCloudFullResHandler);

ros::Publisher pubLaserCloudSurround = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_surround", 100);
("cloud_surround", 100);
ros::Publisher pubLaserCloudSurround_corner = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_surround_corner", 100);
("cloud_surround_corner", 100);

ros::Publisher pubLaserCloudFullRes = nh.advertise<sensor_msgs::PointCloud2>
("/velodyne_cloud_registered", 100);

ros::Publisher pubOdomAftMapped = nh.advertise<nav_msgs::Odometry> ("/aft_mapped_to_init", 1);
ros::Publisher pubOdomAftMapped = nh.advertise<nav_msgs::Odometry> ("odometry", 1);
nav_msgs::Odometry odomAftMapped;
odomAftMapped.header.frame_id = "/camera_init";
odomAftMapped.child_frame_id = "/aft_mapped";
Expand Down
10 changes: 5 additions & 5 deletions src/scanRegistration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -526,24 +526,24 @@ void laserCloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg)
int main(int argc, char** argv)
{
ros::init(argc, argv, "scanRegistration");
ros::NodeHandle nh;
ros::NodeHandle nh("~");

// ros::Subscriber subLaserCloud_for_hk = nh.subscribe<sensor_msgs::PointCloud2>
// ("/livox/lidar", 2, laserCloudHandler_temp);
// pubLaserCloud_for_hk = nh.advertise<sensor_msgs::PointCloud2>
// ("/livox/lidar_temp", 2);

ros::Subscriber subLaserCloud = nh.subscribe<sensor_msgs::PointCloud2>
("/livox/lidar", 100, laserCloudHandler);
("input", 100, laserCloudHandler);
pubLaserCloud = nh.advertise<sensor_msgs::PointCloud2>
("/livox_cloud", 20);
("cloud", 20);

pubCornerPointsSharp = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_sharp", 20);
("cloud_sharp", 20);


pubSurfPointsFlat = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_flat", 20);
("cloud_flat", 20);


ros::spin();
Expand Down