Launch AprilTag
This commit is contained in:
parent
ba03f501b7
commit
ecb6da23eb
12
cfg/apriltag.yaml
Normal file
12
cfg/apriltag.yaml
Normal file
@ -0,0 +1,12 @@
|
||||
# AprilTag 3 code parameters
|
||||
tag_family: 'tag36h11' # options: tagStandard52h13, tagStandard41h12, tag36h11, tag25h9, tag16h5, tagCustom48h12, tagCircle21h7, tagCircle49h12
|
||||
tag_threads: 2 # default: 2
|
||||
tag_decimate: 1.0 # default: 1.0
|
||||
tag_blur: 0.0 # default: 0.0
|
||||
tag_refine_edges: 1 # default: 1
|
||||
tag_debug: 0 # default: 0
|
||||
publish_tf: true # default: false
|
||||
|
||||
# Definitions of tags to detect
|
||||
standalone_tags: [{id: 0, size: 0.091}]
|
||||
tag_bundles: []
|
20
launch/apriltag.launch
Normal file
20
launch/apriltag.launch
Normal file
@ -0,0 +1,20 @@
|
||||
<launch>
|
||||
<!-- Panda -->
|
||||
<include file="$(find active_grasp)/launch/panda.launch" />
|
||||
|
||||
<!-- Camera -->
|
||||
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
|
||||
<arg name="enable_pointcloud" value="true" />
|
||||
<arg name="enable_infra1" value="true" />
|
||||
<arg name="publish_tf" value="false" />
|
||||
</include>
|
||||
|
||||
<!-- AprilTag -->
|
||||
<node pkg="apriltag_ros" type="apriltag_ros_continuous_node" name="apriltag_ros" clear_params="true" output="screen">
|
||||
<rosparam command="load" file="$(find active_grasp)/cfg/apriltag.yaml" />
|
||||
<remap from="image_rect" to="/camera/infra1/image_rect_raw" />
|
||||
<remap from="camera_info" to="/camera/infra1/camera_info" />
|
||||
<param name="camera_frame" type="str" value="camera_depth_optical_frame" />
|
||||
<param name="publish_tag_detections_image" type="bool" value="true" />
|
||||
</node>
|
||||
</launch>
|
13
launch/hw.launch
Normal file
13
launch/hw.launch
Normal file
@ -0,0 +1,13 @@
|
||||
<?xml version="1.0" ?>
|
||||
<launch>
|
||||
|
||||
<!-- Panda -->
|
||||
<include file="$(find active_grasp)/launch/panda.launch" />
|
||||
|
||||
<!-- Camera -->
|
||||
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
|
||||
<arg name="enable_pointcloud" value="true" />
|
||||
<arg name="publish_tf" value="false" />
|
||||
</include>
|
||||
|
||||
</launch>
|
@ -30,10 +30,4 @@
|
||||
<rosparam command="load" file="$(find panda_controllers)/config/controllers.yaml" />
|
||||
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="--stopped position_joint_trajectory_controller cartesian_velocity_controller"/>
|
||||
|
||||
<!-- Camera -->
|
||||
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
|
||||
<arg name="enable_pointcloud" value="true" />
|
||||
<arg name="publish_tf" value="false" />
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
Loading…
x
Reference in New Issue
Block a user