<node pkg="wild_thumper" type="sensor_board.py" name="sensor_board" output="screen"/>
<node pkg="wild_thumper" type="ledstripe.rb" name="led_stripe" output="screen"/>
+
+ <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
+ <param name="serial_port" type="string" value="/dev/rplidar"/>
+ <param name="serial_baudrate" type="int" value="115200"/><!--A1/A2 -->
+ <param name="frame_id" type="string" value="lidar"/>
+ <param name="angle_compensate" type="bool" value="true"/>
+ <param name="scan_mode" type="string" value="Standard"/>
+ <!--
+ A2 scan_modes:
+ Standard: max_distance: 16.0 m, Point number: 2.0K
+ Express: max_distance: 16.0 m, Point number: 4.0K
+ -->
+ </node>
</launch>
<?xml version="1.0"?>
<robot name="wild_thumper" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926535897931" />
- <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
<link name="base_footprint">
<visual>
</visual>
</link>
- <xacro:asus_camera name="camera" parent="mounting_plate">
- <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
- </xacro:asus_camera>
+ <link name="lidar">
+ <visual>
+ <geometry>
+ <mesh filename="package://wild_thumper/meshes/rplidar_a2.stl" scale="0.001 0.001 0.001"/>
+ </geometry>
+ <origin xyz="0.0 0.0 ${0.0408/2}" rpy="0 0 0"/>
+ <material name="black">
+ <color rgba="0 0 0 1"/>
+ </material>
+ </visual>
+ </link>
<link name="sonar_forward_left">
<visual>
</visual>
</link>
- <link name="ir_left">
- <visual>
- <geometry>
- <box size="0.015 0.015 0.046"/>
- </geometry>
- <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
- <material name="black">
- <color rgba="0 0 0 1"/>
- </material>
- </visual>
- </link>
-
- <link name="ir_right">
- <visual>
- <geometry>
- <box size="0.015 0.015 0.046"/>
- </geometry>
- <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
- <material name="black">
- <color rgba="0 0 0 1"/>
- </material>
- </visual>
- </link>
-
<joint name="base_link_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
</joint>
- <joint name="ir_left_joint" type="fixed">
- <parent link="mounting_plate"/>
- <child link="ir_left"/>
- <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
- </joint>
-
- <joint name="ir_right_joint" type="fixed">
+ <joint name="lidar_joint" type="fixed">
<parent link="mounting_plate"/>
- <child link="ir_right"/>
- <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
+ <child link="lidar"/>
+ <origin xyz="0.075 0.01 0.0" rpy="0 0 ${-110*PI/180}"/>
</joint>
<xacro:macro name="wheel" params="pos side xyz rpy">