Skip to content

Commit

Permalink
[perception_toolbox] Fix perception pipelines depends, rs_cam topics (#…
Browse files Browse the repository at this point in the history
…85)

* [perception_pipelines] Fix depends

* Update rs_camera topics
  • Loading branch information
lukeschmitt-tr committed Jan 2, 2025
1 parent 3a6009f commit 18cf53b
Show file tree
Hide file tree
Showing 10 changed files with 38 additions and 48 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,8 @@ Short descriptions for each launch file's arguments are below...
| standalone_tags | individual AprilTags the algorithm should be looking for | refer to [tags.yaml](config/tags.yaml) |
| camera_frame | the camera frame in which the AprilTag will be detected | camera_color_optical_frame |
| apriltag_ns | name-space where the AprilTag related nodes and parameters are located | apriltag |
| camera_color_topic | the absolute ROS topic name to subscribe to color images | camera/color/image_raw |
| camera_info_topic | the absolute ROS topic name to subscribe to the camera color info | camera/color/camera_info |
| camera_color_topic | the absolute ROS topic name to subscribe to color images | /camera/camera/color/image_raw |
| camera_info_topic | the absolute ROS topic name to subscribe to the camera color info | /camera/camera/color/camera_info |

#### armtag.launch

Expand All @@ -102,7 +102,7 @@ Besides for the arguments listed below, the arguments above are in this launch f
| filter_params | file location of the parameters used to tune the perception pipeline filters | "" |
| use_pointcloud_tuner_gui | whether to show a GUI that a user can use to tune filter parameters | false |
| enable_pipeline | whether to enable the perception pipeline filters to run continuously; to save computer processing power, this should be set to False unless you are actively trying to tune the filter parameters; if False, the pipeline will only run if the `get_cluster_positions` ROS service is called | $(arg use_pointcloud_tuner_gui) |
| cloud_topic | the absolute ROS topic name to subscribe to raw pointcloud data | /camera/depth/color/points |
| cloud_topic | the absolute ROS topic name to subscribe to raw pointcloud data | /camera/camera/depth/color/points |

## Troubleshooting

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ def __init__(
# set up subs, pubs, and services
self.node_inf.declare_parameter(
f'/{apriltag_ns}/camera_info_topic',
'/camera/color/camera_info'
'/camera/camera/color/camera_info'
)
camera_info_topic = self.node_inf.get_parameter(
f'/{apriltag_ns}/camera_info_topic').get_parameter_value().string_value.strip('/')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ def __init__(self):

self.declare_parameter(
'camera_color_topic',
'/camera/color/image_raw'
'/camera/camera/color/image_raw'
)
self.declare_parameter(
'apriltag_ns',
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,12 +106,12 @@ def generate_launch_description():
),
DeclareLaunchArgument(
'camera_color_topic',
default_value='camera/color/image_raw',
default_value='/camera/camera/color/image_raw',
description='the absolute ROS topic name to subscribe to color images.',
),
DeclareLaunchArgument(
'camera_info_topic',
default_value='camera/color/camera_info',
default_value='/camera/camera/color/camera_info',
description='the absolute ROS topic name to subscribe to the camera color info.',
),
]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,12 +120,12 @@ def generate_launch_description():
),
DeclareLaunchArgument(
'camera_color_topic',
default_value='camera/color/image_raw',
default_value='/camera/camera/color/image_raw',
description='the absolute ROS topic name to subscribe to color images.',
),
DeclareLaunchArgument(
'camera_info_topic',
default_value='camera/color/camera_info',
default_value='/camera/camera/color/camera_info',
description='the absolute ROS topic name to subscribe to the camera color info.',
),
DeclareLaunchArgument(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ def generate_launch_description():
),
DeclareLaunchArgument(
'cloud_topic',
default_value='camera/depth/color/points',
default_value='/camera/camera/depth/color/points',
description='the absolute ROS topic name to subscribe to raw pointcloud data.',
),
]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,12 @@ def generate_launch_description():
),
DeclareLaunchArgument(
'camera_color_topic',
default_value='/camera/color/image_raw',
default_value='/camera/camera/color/image_raw',
description='topic in which the picture_snapper node can find the raw image message.',
),
DeclareLaunchArgument(
'camera_info_topic',
default_value='/camera/color/camera_info',
default_value='/camera/camera/color/camera_info',
description=(
'topic in which the picture_snapper node can find the camera_info message.'
),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,26 +15,24 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(interbotix_xs_msgs REQUIRED)
find_package(interbotix_perception_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(pcl_conversions REQUIRED)
find_package(pcl_ros REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(visualization_msgs REQUIRED)

set(
PERCEPTION_PIPELINE_ROS_DEPENDENCIES
ament_index_cpp
rclcpp
sensor_msgs
interbotix_perception_msgs
visualization_msgs
pcl_conversions
pcl_ros
rclcpp
sensor_msgs
std_srvs
visualization_msgs
)

add_executable(pointcloud_pipeline src/pointcloud_pipeline.cpp)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,20 +10,14 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>cv_bridge</depend>
<depend>ament_index_cpp</depend>
<depend>interbotix_perception_msgs</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>
<depend>interbotix_xs_msgs</depend>
<depend>interbotix_perception_msgs</depend>
<depend>interbotix_common_modules</depend>
<depend>visualization_msgs</depend>
<depend>std_srvs</depend>
<depend>sensor_msgs</depend>
<depend>rcutils</depend>
<depend>tf_transformations</depend>
<depend>std_srvs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,30 +32,28 @@
#include <vector>

#include "ament_index_cpp/get_package_share_directory.hpp"
#include "pcl/point_cloud.h"
#include "pcl/point_types.h"
#include "pcl/filters/voxel_grid.h"
#include "interbotix_perception_msgs/msg/cluster_info.hpp"
#include "interbotix_perception_msgs/srv/cluster_info_array.hpp"
#include "interbotix_perception_msgs/srv/filter_params.hpp"
#include "pcl_conversions/pcl_conversions.h"
#include "pcl/common/common.h"
#include "pcl/common/transforms.h"
#include "pcl/filters/crop_box.h"
#include "pcl/sample_consensus/model_types.h"
#include "pcl/sample_consensus/method_types.h"
#include "pcl/segmentation/sac_segmentation.h"
#include "pcl/filters/extract_indices.h"
#include "pcl/filters/radius_outlier_removal.h"
#include "pcl/segmentation/extract_clusters.h"
#include "pcl/filters/voxel_grid.h"
#include "pcl/kdtree/kdtree.h"
#include "pcl/common/common.h"
#include "pcl/common/transforms.h"
#include "pcl_conversions/pcl_conversions.h"

#include "pcl/point_cloud.h"
#include "pcl/point_types.h"
#include "pcl/sample_consensus/method_types.h"
#include "pcl/sample_consensus/model_types.h"
#include "pcl/segmentation/extract_clusters.h"
#include "pcl/segmentation/sac_segmentation.h"
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "visualization_msgs/msg/marker.hpp"

#include "interbotix_perception_msgs/msg/cluster_info.hpp"
#include "interbotix_perception_msgs/srv/filter_params.hpp"
#include "interbotix_perception_msgs/srv/cluster_info_array.hpp"

typedef pcl::PointXYZRGB PointT;

using SetBool = std_srvs::srv::SetBool;
Expand Down Expand Up @@ -388,7 +386,7 @@ int main(int argc, char ** argv)

std::string cloud_topic;
node_->declare_parameter<bool>("enable_pipeline", true);
node_->declare_parameter<std::string>("cloud_topic", "/camera/depth/color/points");
node_->declare_parameter<std::string>("cloud_topic", "/camera/camera/depth/color/points");
node_->declare_parameter<float>("voxel_leaf_size", 0.004);
node_->declare_parameter<float>("x_filter_min", -0.25);
node_->declare_parameter<float>("y_filter_min", -0.25);
Expand Down

0 comments on commit 18cf53b

Please sign in to comment.