Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

gz_classic_sim: Free caster wheel joint. #166

Merged
merged 1 commit into from
Oct 9, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 0 additions & 7 deletions andino_gz_classic/launch/spawn_robot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,13 +70,6 @@ def get_robot_description(use_ros_control: str) -> str:
robot_desc = robot_desc.replace(
'package://andino_description/', f'file://{folder}/'
)
# TODO(issue #110). Gazebo simulation with ros control and caster wheel working complete
# made that the robot do not move in straight-line.
# hack to solve the problem of the caster.
robot_desc = robot_desc.replace(
'<joint name="caster_rotation_joint" type="continuous">',
'<joint name="caster_rotation_joint" type="fixed">',
)
return robot_desc


Expand Down
24 changes: 4 additions & 20 deletions andino_gz_classic/urdf/andino_gz_classic.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,24 +3,6 @@

<xacro:include filename="$(find andino_description)/urdf/andino.urdf.xacro"/>

<xacro:macro name="friction" params="reference mu">
<gazebo reference="${reference}">
<mu1>${mu}</mu1>
<mu2>${mu}</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
<minDepth>0.0001</minDepth>
<maxVel>1.0</maxVel>
</gazebo>
</xacro:macro>

<xacro:friction reference="right_wheel" mu="100.0"/>
<xacro:friction reference="left_wheel" mu="100.0"/>
<xacro:friction reference="caster_wheel_link" mu="0.05"/>
<!--TODO(olmerg) initial solution problem with ros control -->
<!-- <xacro:friction reference="caster_rotation_link" mu="0.0"/> -->


<xacro:if value="$(arg use_gazebo_ros_control)">
<ros2_control name="diff_controller" type="system">
<hardware>
Expand Down Expand Up @@ -52,7 +34,8 @@
<remapping>~/out:=joint_states</remapping>
<remapping>/tf:=tf</remapping>
</ros>
<update_rate>10</update_rate>
<update_rate>30</update_rate>
<joint_name>caster_rotation_joint</joint_name>
<joint_name>caster_wheel_joint</joint_name>
</plugin>
</gazebo>
Expand All @@ -65,9 +48,10 @@
<remapping>~/out:=joint_states</remapping>
<remapping>/tf:=tf</remapping>
</ros>
<update_rate>10</update_rate>
<update_rate>30</update_rate>
<joint_name>right_wheel_joint</joint_name>
<joint_name>left_wheel_joint</joint_name>
<joint_name>caster_rotation_joint</joint_name>
<joint_name>caster_wheel_joint</joint_name>
</plugin>

Expand Down