Skip to content
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
1 change: 1 addition & 0 deletions apps/floor_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class FloorDetectionNodelet : public nodelet::Nodelet {
* @param cloud_msg point cloud msg
*/
void cloud_callback(const sensor_msgs::PointCloud2ConstPtr& cloud_msg) {
std::cout << "floor" << std::endl;
pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
pcl::fromROSMsg(*cloud_msg, *cloud);

Expand Down
1 change: 1 addition & 0 deletions apps/prefiltering_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,7 @@ class PrefilteringNodelet : public nodelet::Nodelet {
points_pub.publish(*filtered);
}


pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
if(!downsample_filter) {
return cloud;
Expand Down
1 change: 1 addition & 0 deletions apps/scan_matching_odometry_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,7 @@ class ScanMatchingOdometryNodelet : public nodelet::Nodelet {

read_until->frame_id = "/filtered_points";
read_until_pub.publish(read_until);
// std::cout << "PointCloud2ConstPtr ..." << std::endl;
}

void msf_pose_callback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose_msg, bool after_update) {
Expand Down
8 changes: 5 additions & 3 deletions launch/hdl_graph_slam.launch
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,11 @@
<!-- ***** map -> odom -> base_link -> velodyne ***** -->
<!-- these can be named in the following -->
<!-- topic for hdl to find velodyne points -->
<arg name="points_topic" default="/velodyne_points" />
<arg name="points_topic" default="/D435_head_camera/depth/color/points" />
<!-- what should the map frame be called -->
<arg name="map_frame_id" default="map" />
<!-- what should the base link frame be called -->
<arg name="base_link_frame_id" default="base_link" />
<arg name="base_link_frame_id" default="pelvis" />
<!-- what should the odom frame be called -->
<arg name="lidar_odom_frame_id" default="odom" />

Expand All @@ -28,7 +28,7 @@
<arg name="robot_odom_frame_id" default="robot_odom" />

<!-- transformation between lidar and base_link -->
<node pkg="tf" type="static_transform_publisher" name="lidar2base_publisher" args="0 0 0 0 0 0 $(arg base_link_frame_id) velodyne 10" />
<!-- <node pkg="tf" type="static_transform_publisher" name="lidar2base_publisher" args="0 0 0 0 0 0 $(arg base_link_frame_id) D435_head_camera_link 10" /> -->

<!-- in case you use velodyne_driver, comment out the following line -->
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" output="screen"/>
Expand Down Expand Up @@ -93,6 +93,7 @@
<param name="normal_filter_thresh" value="20.0" />
</node>


<!-- hdl_graph_slam_nodelet -->
<node pkg="nodelet" type="nodelet" name="hdl_graph_slam_nodelet" args="load hdl_graph_slam/HdlGraphSlamNodelet $(arg nodelet_manager)">
<param name="points_topic" value="$(arg points_topic)" />
Expand Down Expand Up @@ -173,4 +174,5 @@
<param name="map_frame_id" value="$(arg map_frame_id)" />
<param name="odom_frame_id" value="$(arg lidar_odom_frame_id)" />
</node>

</launch>