Skip to content
Snippets Groups Projects
Commit 708f06c6 authored by Shengkang (William) Chen's avatar Shengkang (William) Chen
Browse files

adding launch files and scripts

parent f30493d7
No related merge requests found
<launch>
<arg name="markerId" default="701"/>
<arg name="markerSize" default="0.05"/> <!-- in meter -->
<arg name="eye" default="left"/>
<arg name="marker_frame" default="marker_frame"/>
<arg name="ref_frame" default=""/> <!-- leave empty and the pose will be published wrt param parent_name -->
<arg name="corner_refinement" default="LINES" /> <!-- NONE, HARRIS, LINES, SUBPIX -->
<node pkg="aruco_ros" type="single" name="aruco_single">
<remap from="/camera_info" to="/usb_cam/camera_info" />
<remap from="/image" to="/usb_cam/image_raw" />
<param name="image_is_rectified" value="True"/>
<param name="marker_size" value="$(arg markerSize)"/>
<param name="marker_id" value="$(arg markerId)"/>
<param name="reference_frame" value="$(arg ref_frame)"/> <!-- frame in which the marker pose will be refered -->
<param name="camera_frame" value="base_link"/>
<param name="marker_frame" value="$(arg marker_frame)" />
<param name="corner_refinement" value="$(arg corner_refinement)" />
</node>
</launch>
<!-- Run the aruco_detect node -->
<launch>
<!-- namespace for camera input -->
<arg name="camera" default="/usb_cam"/>
<arg name="image" default="image"/>
<arg name="transport" default="raw"/>
<arg name="fiducial_len" default="0.14"/>
<arg name="dictionary" default="7"/>
<arg name="do_pose_estimation" default="true"/>
<node pkg="aruco_detect" name="aruco_detect"
type="aruco_detect" output="screen" respawn="false">
<param name="image_transport" value="$(arg transport)"/>
<param name="publish_images" value="true" />
<param name="fiducial_len" value="$(arg fiducial_len)"/>
<param name="dictionary" value="$(arg dictionary)"/>
<param name="do_pose_estimation" value="$(arg do_pose_estimation)"/>
<remap from="/camera" to="/usb_cam/image_raw" />
<remap from="/camera_info" to="$(arg camera)/camera_info"/>
</node>
</launch>
#!/bin/bash
cd $HOME/catkin_ws
xterm -hold -e "roscore" &
xterm -hold -e "roslaunch usb_cam_stream_publisher.launch" &
sleep 5
xterm -hold -e "roslaunch aruco_markers_detect.launch" &
sleep 3
xterm -hold -e "rosrun image_view image_view image:=/fiducial_images" &
xterm -hold -e "rostopic echo /fiducial_transforms" &
sleep 2
xterm -hold -e "rosrun topic_tools throttle messages /fiducial_transforms 5.0" &
xterm -hold -e "rostopic hz fiducial_transforms_throttle"
cd $HOME/
exit 0
<<COMMENT
For the throttle frequencies:
Issues: throttle rates lower than expected(default rate = 30Hz)
Expected rate [Hz]: Real rate [Hz]:
40 ~30
30 19.5~20
20 ~15
15 ~10.5
10 ~8.4
8 ~7.5
4 ~3.75
1 0.98
COMMENT
cal.yml 0 → 100644
image_width: 640
image_height: 480
camera_name: narrow_stereo
camera_matrix:
rows: 3
cols: 3
data: [654.029002, 0, 318.310629, 0, 651.6204770000001, 210.721894, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.006783, -0.178923, 0.000926, 0.007013999999999999, 0]
rectification_matrix:
rows: 3
cols: 3
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
rows: 3
cols: 4
data: [645.730774, 0, 321.784936, 0, 0, 649.168945, 210.480637, 0, 0, 0, 1, 0]
......@@ -10,8 +10,8 @@ def ang_vel(lvel, rvel):
if ((lvel - rvel) != 0):
v1 = float(lvel)
v2 = float(rvel)
r1 = (v2 * .35)/(v2-v1)
w = v2/r1
r1 = (v1 * .35)/(v2-v1)
w = v1/r1
return w
def callback(data):
......
<!--
Example of run:
roslaunch usb_cam_stream_publisher.launch video_device:=/dev/video0 image_width:=640 image_height:=480
-->
<launch>
<arg name="video_device" default="/dev/video1" />
<arg name="image_width" default="640" />
<arg name="image_height" default="480" />
<arg name="image_topic_name" default="/usb_cam/image_raw" />
<arg name="camera_info_topic_name" default="/usb_cam/camera_info" />
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="$(arg video_device)" />
<param name="image_width" value="$(arg image_width)" />
<param name="image_height" value="$(arg image_height)"/>
<param name="pixel_format" value="mjpeg" />
<param name="io_method" value="mmap"/>
<!-- update these line accroding to your setting, here are some examples:-->
<!-- <param name="camera_info_url" value="package://your_cameras/info/camera.yaml"/> -->
<param name="camera_info_url" value="file:///home/ucla/catkin_ws/cal.yml"/> <!-- <param name="camera_info_url" value="file://${ROS_HOME}/camera_info/head_camera.yaml"/> -->
<remap from="/usb_cam/camera_info" to="$(arg camera_info_topic_name)"/>
<remap from="/usb_cam/image_raw" to="$(arg image_topic_name)"/>
</node>
</launch>
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment