follower2.launch 1.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657
  1. <launch>
  2. <node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" />
  3. <!-- Run a VoxelGrid filter on the z axis -->
  4. <node pkg="nodelet" type="nodelet" name="voxel_grid_z" args="load pcl/VoxelGrid pcl_manager" output="screen">
  5. <remap from="~input" to="/camera/depth_registered/points" />
  6. <remap from="~output" to="/z_filtered" />
  7. <rosparam>
  8. filter_field_name: z
  9. filter_limit_min: 0.3
  10. filter_limit_max: 1.6
  11. filter_limit_negative: False
  12. leaf_size: 0.02
  13. </rosparam>
  14. </node>
  15. <!-- Run a passthrough filter on the x axis -->
  16. <node pkg="nodelet" type="nodelet" name="passthrough_x" args="load pcl/PassThrough pcl_manager" output="screen">
  17. <remap from="~input" to="/z_filtered" />
  18. <remap from="~output" to="/x_filtered" />
  19. <rosparam>
  20. filter_field_name: x
  21. filter_limit_min: -0.3
  22. filter_limit_max: 0.3
  23. filter_limit_negative: False
  24. </rosparam>
  25. </node>
  26. <!-- Run a passthrough filter on the y axis -->
  27. <node pkg="nodelet" type="nodelet" name="passthrough_y" args="load pcl/PassThrough pcl_manager" output="screen">
  28. <remap from="~input" to="/x_filtered" />
  29. <remap from="~output" to="/search_cloud" />
  30. <rosparam>
  31. filter_field_name: y
  32. filter_limit_min: -0.5
  33. filter_limit_max: -0.1
  34. filter_limit_negative: False
  35. </rosparam>
  36. </node>
  37. <node pkg="rbx1_apps" name="follower" type="follower2.py" output="screen">
  38. <remap from="point_cloud" to="search_cloud" />
  39. <rosparam>
  40. goal_z: 0.8
  41. z_threshold: 0.025
  42. x_threshold: 0.025
  43. z_scale: 1.0
  44. x_scale: 3.0
  45. max_angular_speed: 5.0
  46. min_angular_speed: 0.1
  47. max_linear_speed: 0.4
  48. min_linear_speed: 0.05
  49. </rosparam>
  50. </node>
  51. </launch>