urdf cast wheel debug

This commit is contained in:
Ly PECHVATTANA 2023-08-30 01:25:34 -07:00
parent 462780d2af
commit c06338a682
2 changed files with 31 additions and 13 deletions

View File

@ -212,7 +212,7 @@
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/> <origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
</joint> --> </joint> -->
<joint name="caster__joint" type="fixed"> <joint name="caster_joint" type="fixed">
<parent link="base_link"/> <parent link="base_link"/>
<child link="caster_link"/> <child link="caster_link"/>
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/> <origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>

View File

@ -32,18 +32,7 @@
<material>Gazebo/FlatBlack</material> <material>Gazebo/FlatBlack</material>
</gazebo> </gazebo>
<gazebo reference="caster_back_right_link"> <gazebo reference="caster_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>1000000</kp>
<kd>100</kd>
<minDepth>0.001</minDepth>
<maxVel>1</maxVel>
<fdir1>1 0 0</fdir1>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="caster_back_left_link">
<mu1>0.1</mu1> <mu1>0.1</mu1>
<mu2>0.1</mu2> <mu2>0.1</mu2>
<kp>1000000</kp> <kp>1000000</kp>
@ -82,4 +71,33 @@
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</actuator> </actuator>
</transmission> </transmission>
<gazebo reference="base_scan">
<sensor name="laser" type="ray">
<pose> 0 0 0 0 0 0 </pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
</scan>
<range>
<min>0.3</min>
<max>12</max>
</range>
</ray>
<plugin name="laser_controller" filename="libgazebo_ros_ray_sensor.so">
<ros>
<argument>~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>laser_frame</frame_name>
</plugin>
</sensor>
</gazebo>
</robot> </robot>