Skip to content
Closed
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
5 changes: 1 addition & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,9 @@ cmake_minimum_required(VERSION 3.8)
project(simulation)
find_package(ament_cmake REQUIRED)

file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/models/curiosity_path)

install(DIRECTORY
models
${CMAKE_CURRENT_BINARY_DIR}/models
DESTINATION share/${PROJECT_NAME}/
DESTINATION share/${PROJECT_NAME}
)

ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in")
Expand Down
3 changes: 1 addition & 2 deletions hooks/simulation.dsv.in
Original file line number Diff line number Diff line change
@@ -1,2 +1 @@
prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share
prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share/simulation/models
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share
10 changes: 4 additions & 6 deletions models/canadarm/urdf/SSRMS_Canadarm2.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@
<xacro:macro name="ssrms_canadarm2_gazebo" params="command_interface:=effort">


<ros2_control name="IgnitionSystem" type="system">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="Base_Joint">
<command_interface name="${command_interface}"/>
Expand Down Expand Up @@ -53,10 +53,8 @@
</ros2_control>

<gazebo>
<plugin filename="libign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<robot_param>robot_description</robot_param>
<robot_param_node>robot_state_publisher</robot_param_node>
<parameters>$(find canadarm)/config/canadarm_control.yaml</parameters>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<parameters>$(find canadarm)/config/canadarm_control.yaml</parameters>
</plugin>
</gazebo>

Expand Down
168 changes: 81 additions & 87 deletions models/curiosity_path/urdf/arm.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,10 @@

<link name='arm_01'>
<collision>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
Expand Down Expand Up @@ -69,17 +68,6 @@
<dynamics damping="0.0" friction="0.0"/>
</joint>

<transmission name="arm_01_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_01_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="arm_01Motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<link name='arm_01_to_arm_02'>
<inertial>
Expand Down Expand Up @@ -137,7 +125,6 @@
</inertial>
</link>


<joint name="arm_02_joint" type="revolute">
<parent link="arm_01_to_arm_02"/>
<child link="arm_02"/>
Expand All @@ -147,18 +134,6 @@
<dynamics damping="0.0" friction="0.0"/>
</joint>

<transmission name="arm_02_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_02_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="arm_02Motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<link name='arm_02_to_arm_03'>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand Down Expand Up @@ -225,19 +200,6 @@
<dynamics damping="0.0" friction="0.0"/>
</joint>

<transmission name="arm_03_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_03_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="arm_03Motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>



<link name='arm_03_to_arm_04'>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand Down Expand Up @@ -267,24 +229,21 @@

<link name='arm_04'>
<collision>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_04_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_04_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

<inertial>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${arm_04_Mass}"/>
<xacro:box_inertia
m="${arm_04_Mass}"
Expand All @@ -304,36 +263,24 @@
<dynamics damping="0.0" friction="0.0"/>
</joint>

<transmission name="arm_04_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_04_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="arm_04Motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<link name='arm_04_to_arm_tools'>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.02" />
<inertia ixx="2.61666666667e-05" ixy="0.0" ixz="0.0" iyy="2.61666666667e-05" iyz="0.0" izz="3.6e-05"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.02"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.02"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.02" />
<inertia ixx="2.61666666667e-05" ixy="0.0" ixz="0.0" iyy="2.61666666667e-05" iyz="0.0" izz="3.6e-05"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.02"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.02" length="0.02"/>
</geometry>
</visual>
</link>


Expand All @@ -346,24 +293,21 @@

<link name='arm_tools'>
<collision>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_tools_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_tools_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

<inertial>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${arm_tools_Mass}"/>
<xacro:box_inertia
m="${arm_tools_Mass}"
Expand All @@ -373,7 +317,6 @@
</inertial>
</link>


<joint name="arm_tools_joint" type="continuous">
<parent link="arm_04_to_arm_tools"/>
<child link="arm_tools"/>
Expand All @@ -383,17 +326,68 @@
<dynamics damping="0.0" friction="0.0"/>
</joint>

</xacro:macro>

<!-- ros2_control transmission does NOT use this currently. This macro is not actively used -->
<xacro:macro name="arm_transmission" params="hw_interface:=hardware_interface/EffortJointInterface">

<transmission name="arm_01_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_01_joint">
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="arm_01Motor">
<hardwareInterface>${hw_interface}</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="arm_02_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_02_joint">
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="arm_02Motor">
<hardwareInterface>${hw_interface}</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<transmission name="arm_03_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_03_joint">
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="arm_03Motor">
<hardwareInterface>${hw_interface}</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<transmission name="arm_04_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_04_joint">
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="arm_04Motor">
<hardwareInterface>${hw_interface}</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<transmission name="arm_tools_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="arm_tools_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="arm_toolsMotor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

</xacro:macro>

</robot>
12 changes: 6 additions & 6 deletions models/curiosity_path/urdf/curiosity_mars_rover.gazebo
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">

<ros2_control name="IgnitionSystem" type="system">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<!-- Arm Joints Interfaces-->
<joint name="arm_01_joint">
Expand Down Expand Up @@ -132,27 +132,27 @@
</ros2_control>

<gazebo>
<plugin filename="libign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<robot_param>robot_description</robot_param>
<robot_param_node>robot_state_publisher</robot_param_node>
<parameters>$(find mars_rover)/config/mars_rover_control.yaml</parameters>
</plugin>

<plugin filename="ignition-gazebo-odometry-publisher-system" name="ignition::gazebo::systems::OdometryPublisher">
<plugin filename="gz-sim-odometry-publisher-system" name="gz::sim::systems::OdometryPublisher">
<odom_frame>/odom</odom_frame>
<robot_base_frame>/base_footprint</robot_base_frame>
<odom_publish_frequency>10</odom_publish_frequency>
</plugin>

<plugin filename="ignition-gazebo-sensors-system" name="ignition::gazebo::systems::Sensors">
<plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
<background_color>0.9 0.753 0.66 1</background_color>
</plugin>
</gazebo>

<gazebo reference="lidar_link">
<sensor name='lidar' type='gpu_lidar'>"
<ignition_frame_id>lidar_link</ignition_frame_id>
<gz_frame_id>lidar_link</gz_frame_id>
<pose relative_to='lidar_link'>0 0 0 0 0 0</pose>
<topic>scan</topic>
<update_rate>10</update_rate>
Expand Down
Loading
Loading