diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/README.md b/interbotix_perception_toolbox/interbotix_perception_modules/README.md index da99e2e0..1d0a8faf 100644 --- a/interbotix_perception_toolbox/interbotix_perception_modules/README.md +++ b/interbotix_perception_toolbox/interbotix_perception_modules/README.md @@ -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 @@ -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 diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/apriltag.py b/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/apriltag.py index 88ac575c..c92fcfb2 100644 --- a/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/apriltag.py +++ b/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/apriltag.py @@ -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('/') diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/picture_snapper.py b/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/picture_snapper.py index 03bb5f96..bb15f3c7 100755 --- a/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/picture_snapper.py +++ b/interbotix_perception_toolbox/interbotix_perception_modules/interbotix_perception_modules/picture_snapper.py @@ -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', diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/launch/apriltag.launch.py b/interbotix_perception_toolbox/interbotix_perception_modules/launch/apriltag.launch.py index 2a447121..ff83d9b4 100644 --- a/interbotix_perception_toolbox/interbotix_perception_modules/launch/apriltag.launch.py +++ b/interbotix_perception_toolbox/interbotix_perception_modules/launch/apriltag.launch.py @@ -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.', ), ] diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/launch/armtag.launch.py b/interbotix_perception_toolbox/interbotix_perception_modules/launch/armtag.launch.py index 29e1a387..b357a65f 100644 --- a/interbotix_perception_toolbox/interbotix_perception_modules/launch/armtag.launch.py +++ b/interbotix_perception_toolbox/interbotix_perception_modules/launch/armtag.launch.py @@ -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( diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/launch/pc_filter.launch.py b/interbotix_perception_toolbox/interbotix_perception_modules/launch/pc_filter.launch.py index c244f7c1..d7731dfb 100644 --- a/interbotix_perception_toolbox/interbotix_perception_modules/launch/pc_filter.launch.py +++ b/interbotix_perception_toolbox/interbotix_perception_modules/launch/pc_filter.launch.py @@ -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.', ), ] diff --git a/interbotix_perception_toolbox/interbotix_perception_modules/launch/picture_snapper.launch.py b/interbotix_perception_toolbox/interbotix_perception_modules/launch/picture_snapper.launch.py index 35b4577c..c9f61031 100644 --- a/interbotix_perception_toolbox/interbotix_perception_modules/launch/picture_snapper.launch.py +++ b/interbotix_perception_toolbox/interbotix_perception_modules/launch/picture_snapper.launch.py @@ -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.' ), diff --git a/interbotix_perception_toolbox/interbotix_perception_pipelines/src/pointcloud_pipeline.cpp b/interbotix_perception_toolbox/interbotix_perception_pipelines/src/pointcloud_pipeline.cpp index fff83da6..6f81ddbc 100644 --- a/interbotix_perception_toolbox/interbotix_perception_pipelines/src/pointcloud_pipeline.cpp +++ b/interbotix_perception_toolbox/interbotix_perception_pipelines/src/pointcloud_pipeline.cpp @@ -386,7 +386,7 @@ int main(int argc, char ** argv) std::string cloud_topic; node_->declare_parameter("enable_pipeline", true); - node_->declare_parameter("cloud_topic", "/camera/depth/color/points"); + node_->declare_parameter("cloud_topic", "/camera/camera/depth/color/points"); node_->declare_parameter("voxel_leaf_size", 0.004); node_->declare_parameter("x_filter_min", -0.25); node_->declare_parameter("y_filter_min", -0.25);