-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathrobot.launch
More file actions
83 lines (63 loc) · 3.46 KB
/
robot.launch
File metadata and controls
83 lines (63 loc) · 3.46 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
<launch>
<node pkg="omron_os32c_driver" type="omron_os32c_node" name="omron_laser_1">
<param name="host" value="192.168.1.80" />
<param name="local_ip" value="192.168.1.70" />
<param name="frame_id" value="base_omron1" />
<remap from="scan" to="omron_scan1"/>
</node>
<node pkg="omron_os32c_driver" type="omron_os32c_node" name="omron_laser_2">
<param name="host" value="192.168.2.81" />
<param name="local_ip" value="192.168.2.71" />
<param name="frame_id" value="base_omron2" />
<remap from="scan" to="omron_scan2"/>
</node>
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter1">
<rosparam command="load" file="single_laser_filter_right.yaml" />
<remap from="scan" to="/omron_scan1" />
<remap from="scan_filtered" to="/omron_scan1_filtered" />
</node>
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter2">
<rosparam command="load" file="single_laser_filter_right.yaml" />
<remap from="scan" to="/omron_scan2" />
<remap from="scan_filtered" to="/omron_scan2_filtered" />
</node>
<!-- laser data merge -->
<node pkg="ira_laser_tools" name="laserscan_multi_merger1" type="laserscan_multi_merger">
<param name="destination_frame" value="/base_laser_link"/>
<param name="scan_destination_topic" value="/scan_multi"/>
<param name="laserscan_topics" value ="/omron_scan2_filtered /omron_scan1_filtered" />
<param name="angle_min" value="-360"/>
<param name="angle_max" value="360"/>
<param name="range_min" value="0.45"/>
<param name="range_max" value="100"/>
</node>
<!-- differential robot drive -->
<node pkg="diff_drive" type="diff_drive_odometry" name="diff_drive_odometry">
<!-- set a private parameter for the node -->
<param name="encoder_max" value="100000000" />
<param name="encoder_min" value="-100000000" />
<param name="ticks_per_meter" value="26525" />
<param name="wheel_separation" value="0.48" />
</node>
<!-- speed controller, take /cmd_vel commands -->
<node pkg="diff_drive" type="diff_drive_controller" name="diff_drive_controller">
<!-- set a private parameter for the node -->
<param name="max_motor_speed" value="500" />
<param name="ticks_per_meter" value="26525" />
<param name="wheel_separation" value="0.21" />
</node>
<node pkg="robot_setup_tf" type="tf_broadcaster" name="tf_broadcaster"></node>
<node pkg="wheel" type="base_control" name="base_control"></node>
<node pkg="joy" type="joy_node" name="joy_node" output="screen"></node>
<node pkg="keyboard_pub" type="keyboard_pub_node" name="keyboard_pub_node"></node>
<node pkg="keyboard_cont" type="keyboard_cont.py" name="keyboard_cont_node" output="screen"></node>
<node pkg="teleop_twist_joy" type="teleop_node" name="teleop_node">
<param name="scale_linear" value="0.1"/>
<param name="scale_angular" value="0.1"/>
</node>
<!-- upload urdf -->
<param name="robot_description" textfile="wombat.urdf" />
<!-- robot state publisher -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
<node pkg="system_control" type="system_control" name="system_control" />
</launch>