Skip to content

Commit

Permalink
Successfully launched meldog in custom world in gazebo sim with ros2 …
Browse files Browse the repository at this point in the history
…control
  • Loading branch information
BartlomiejK2 committed Sep 15, 2024
1 parent f9e3e92 commit bb27e4c
Show file tree
Hide file tree
Showing 6 changed files with 48 additions and 43 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
<!-- Gazebo macro for links -->
<xacro:property name="kp_value" value="25000.0"/>
<xacro:property name="kd_value" value="0.15"/>
<xacro:property name="mu2_value" value="0.7"/>
<xacro:property name="mu2_value" value="0.7"/>
<xacro:property name="mu2_value" value="0.9"/>
<xacro:property name="mu2_value" value="0.9"/>
<xacro:property name="maxVel_value" value="0.25"/>
<xacro:property name="dampingFactor_value" value="0.00"/>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@
<parent link="thigh_front_left_link"/>
<child link="shank_front_left_link"/>
<axis xyz="0.0 -1.0 0.0"/>
<xacro:meldog_joint_limits lower ="-${PI/2}" upper = "${PI/2}"/>
<xacro:meldog_joint_limits lower ="-${5*PI/6}" upper = "${5*PI/6}"/>
</joint>

<!-- Thigh front right to Shank front right -->
Expand All @@ -143,7 +143,7 @@
<parent link="thigh_front_right_link"/>
<child link="shank_front_right_link"/>
<axis xyz="0.0 -1.0 0.0"/>
<xacro:meldog_joint_limits lower ="-${PI/2}" upper = "${PI/2}"/>
<xacro:meldog_joint_limits lower ="-${5*PI/6}" upper = "${5*PI/6}"/>
</joint>

<!-- Thigh back left to Shank back left -->
Expand All @@ -152,7 +152,7 @@
<parent link="thigh_back_left_link"/>
<child link="shank_back_left_link"/>
<axis xyz="0.0 1.0 0.0"/>
<xacro:meldog_joint_limits lower ="-${PI/2}" upper = "${PI/2}"/>
<xacro:meldog_joint_limits lower ="-${5*PI/6}" upper = "${5*PI/6}"/>
</joint>

<!-- Thigh back right to Shank back right -->
Expand All @@ -161,7 +161,7 @@
<parent link="thigh_back_right_link"/>
<child link="shank_back_right_link"/>
<axis xyz="0.0 1.0 0.0"/>
<xacro:meldog_joint_limits lower ="-${PI/2}" upper = "${PI/2}"/>
<xacro:meldog_joint_limits lower ="-${5*PI/6}" upper = "${5*PI/6}"/>
</joint>


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@


<!-- Thighs to Shanks joints -->
<xacro:ros2_control_joint joint_name="FLS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FRS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BLS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="BRS" lower="-${PI/2}" upper="${PI/2}"/>
<xacro:ros2_control_joint joint_name="FLS" lower="-${5*PI/6}" upper="${5*PI/6}"/>
<xacro:ros2_control_joint joint_name="FRS" lower="-${5*PI/6}" upper="${5*PI/6}"/>
<xacro:ros2_control_joint joint_name="BLS" lower="-${5*PI/6}" upper="${5*PI/6}"/>
<xacro:ros2_control_joint joint_name="BRS" lower="-${5*PI/6}" upper="${5*PI/6}"/>

</ros2_control>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,14 +128,19 @@ def generate_launch_description():
)

# Bridge between ros2 and Ignition Gazebo
ros2_gazebo_sim_bridge = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory('ros_ign_gazebo'),
'launch', 'ign_gazebo.launch.py')]),
launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])])
# ros2_gazebo_sim_bridge = IncludeLaunchDescription(
# PythonLaunchDescriptionSource(
# [os.path.join(get_package_share_directory('ros_ign_gazebo'),
# 'launch', 'ign_gazebo.launch.py')]),
# launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])])
gazebo_sim_bridge = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('ros_gz_sim'), 'launch'), '/gz_sim.launch.py']),
launch_arguments={'gz_args': ['-r -v -v4 ', world], 'on_exit_shutdown': 'true'}.items()
)

nodes = [
ros2_gazebo_sim_bridge,
gazebo_sim_bridge,

RegisterEventHandler(
event_handler=OnProcessExit(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,62 +58,62 @@ joint_trajectory_controller:

gains:
FLH_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
FRH_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
BLH_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
BRH_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
FLT_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
FRT_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
BLT_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
BRT_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
FLS_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
FRS_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
BLS_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
BRS_joint:
d: 2.5
d: 100.0
i: 0.0
i_clamp: 0.0
p: 350.0
p: 1500.0
6 changes: 3 additions & 3 deletions src/meldog_simple_description/worlds/empty.world
Original file line number Diff line number Diff line change
Expand Up @@ -49,13 +49,13 @@
</gui>

<physics type="ode">
<real_time_update_rate>2000.0</real_time_update_rate>
<max_step_size>0.001</max_step_size>
<real_time_update_rate>2500.0</real_time_update_rate>
<max_step_size>0.0005</max_step_size>
<real_time_factor>1</real_time_factor>
<ode>
<solver>
<type>quick</type>
<iters>150</iters>
<iters>200</iters>
<precon_iters>0</precon_iters>
<sor>1.400000</sor>
<use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
Expand Down

0 comments on commit bb27e4c

Please sign in to comment.