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

Description fixes #200

Merged
merged 5 commits into from
Mar 8, 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
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ def generate_launch_description():
executable='joint_state_publisher',
name='joint_state_publisher',
output='screen',
parameters=[{'use_sim_time': True}],
)

# Define LaunchDescription variable
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ functional, while the 4 remaining ones are created as dummy links. -->
<link name="${link_name}"/>
</xacro:macro>

<xacro:macro name="bumper" params="name:=bump_front_center parent_link:=base_link update_rate:=62.0 gazebo visual_mesh collision_mesh
<xacro:macro name="bumper" params="name:=bumper parent_link:=base_link update_rate:=62.0 gazebo visual_mesh collision_mesh
*origin *inertial">
<xacro:property name="link_name" value="${name}"/>
<xacro:property name="joint_name" value="${name}_joint"/>
Expand Down Expand Up @@ -67,6 +67,11 @@ functional, while the 4 remaining ones are created as dummy links. -->
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>

<xacro:dummy_bumper_zone
name="bump_front_center">
<origin xyz="0.175 0 0.039" rpy="0 0 0"/>
</xacro:dummy_bumper_zone>

<xacro:dummy_bumper_zone
name="bump_front_left">
<origin xyz="0.02345 -0.0875 0.025" rpy="0 0 0.5235985"/>
Expand Down