improved iisy_config module
This commit is contained in:
@@ -13,8 +13,6 @@ find_package(ament_cmake REQUIRED)
|
||||
|
||||
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
|
||||
install(DIRECTORY world DESTINATION share/${PROJECT_NAME})
|
||||
install(DIRECTORY urdf DESTINATION share/${PROJECT_NAME})
|
||||
install(DIRECTORY stl DESTINATION share/${PROJECT_NAME})
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
|
||||
Binary file not shown.
@@ -4,7 +4,7 @@ from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from launch.actions import IncludeLaunchDescription, SetEnvironmentVariable, UnsetEnvironmentVariable
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch.substitutions import Command
|
||||
from launch.substitutions import Command, LaunchConfiguration
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
@@ -118,18 +118,15 @@ def generate_launch_description():
|
||||
output='screen'
|
||||
),
|
||||
|
||||
Node(
|
||||
package='gazebo_ros',
|
||||
executable='spawn_entity.py',
|
||||
arguments=['-entity', robot_name,
|
||||
'-topic', 'robot_description',
|
||||
'-x', '-1',
|
||||
'-y', '-1',
|
||||
'-z', '1',
|
||||
'-Y', '0'], # Yaw
|
||||
output='screen'
|
||||
),
|
||||
|
||||
#Node(
|
||||
# package="gazebo_ros",
|
||||
# executable="spawn_entity.py",
|
||||
# arguments=[
|
||||
# "-topic", "robot_description",
|
||||
# "-entity", LaunchConfiguration("iisy")
|
||||
# ],
|
||||
# output="screen"
|
||||
#),
|
||||
|
||||
#Node(
|
||||
# package='robot_state_publisher',
|
||||
@@ -159,21 +156,30 @@ def generate_launch_description():
|
||||
# arguments=["test.xml"]
|
||||
# )
|
||||
|
||||
Node(
|
||||
package='controller_manager',
|
||||
name='gazebo_controller_spawner',
|
||||
executable='spawner',
|
||||
output='screen',
|
||||
parameters=[
|
||||
controllers_yaml,
|
||||
]
|
||||
),
|
||||
|
||||
#Node(package='moveit_ros_move_group',
|
||||
# executable='move_group',
|
||||
# #prefix='xterm -fs 10 -e gdb --ex run --args',
|
||||
# output='screen',
|
||||
# parameters=[
|
||||
# robot_description,
|
||||
# robot_description_semantic,
|
||||
# kinematics_yaml,
|
||||
# ompl_planning_pipeline_config,
|
||||
# trajectory_execution,
|
||||
# moveit_controllers,
|
||||
# planning_scene_monitor_parameters,
|
||||
# #octomap_config,
|
||||
# #octomap_updater_config
|
||||
# ]
|
||||
#)
|
||||
Node(package='moveit_ros_move_group',
|
||||
executable='move_group',
|
||||
#prefix='xterm -fs 10 -e gdb --ex run --args',
|
||||
output='screen',
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
kinematics_yaml,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
planning_scene_monitor_parameters,
|
||||
#octomap_config,
|
||||
#octomap_updater_config
|
||||
]
|
||||
),
|
||||
])
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@@ -1,258 +0,0 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="iisy">
|
||||
<link name="world"/>
|
||||
<link name="base_link"/>
|
||||
<link name="base">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/base_bottom_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/base_bottom_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0.025 0 0.05" rpy="0 0 0"/>
|
||||
<mass value="6"/>
|
||||
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="base_top">
|
||||
<collision>
|
||||
<origin xyz="0 -0.005 0.08"/>
|
||||
<geometry>
|
||||
<box size="0.14 0.15 0.16"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/base_top_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.155" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.0032666666666667" ixy="0.0" ixz="0.0" iyy="0.0032666666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link1_full">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_1_full_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_1_full_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.36" rpy="0 0 0"/>
|
||||
<mass value="4"/>
|
||||
<inertia ixx="0.0325" ixy="0.0" ixz="0.0" iyy="0.0325" iyz="0.0" izz="0.005"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link2_bottom">
|
||||
<collision>
|
||||
<origin xyz="0 0.07 0.025"/>
|
||||
<geometry>
|
||||
<box size="0.14 0.14 0.19"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_2_bottom_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.585" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link2_top">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_2_top_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_2_top_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.735" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link3_bottom">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_bottom_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_bottom_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.86" rpy="0 0 0"/>
|
||||
<mass value="2"/>
|
||||
<inertia ixx="0.0029166666666667" ixy="0.0" ixz="0.0" iyy="0.0029166666666667" iyz="0.0" izz="0.0025"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<link name="link3_top">
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_top_coll.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find gaz_simulation)/stl/link_3_top_low.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.94025" rpy="0 0 0"/>
|
||||
<mass value="0.8"/>
|
||||
<inertia ixx="0.00074401666666667" ixy="0.0" ixz="0.0" iyy="0.00074401666666667" iyz="0.0" izz="0.001"/>
|
||||
</inertial>
|
||||
|
||||
</link>
|
||||
<joint type="fixed" name="world_base_link_fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<parent link="world"/>
|
||||
<child link="base_link"/>
|
||||
</joint>
|
||||
<joint type="fixed" name="base_base_link_fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="base"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="base_rot">
|
||||
<origin xyz="0 0 0.1205" rpy="0 0 0"/>
|
||||
<parent link="base"/>
|
||||
<child link="base_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<joint type="revolute" name="base_link1_joint">
|
||||
<origin xyz="0 -0.080499 0.092997" rpy="0 0 0"/>
|
||||
<parent link="base_top"/>
|
||||
<child link="link1_full"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-2.2689280275926" upper="2.4434609527921"/>
|
||||
</joint>
|
||||
<joint type="revolute" name="link1_link2_joint">
|
||||
<origin xyz="0 0 0.3" rpy="0 0 0"/>
|
||||
<parent link="link1_full"/>
|
||||
<child link="link2_bottom"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943" lower="-2.6179938779915" upper="2.6179938779915"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="link2_rot">
|
||||
<origin xyz="0 0.080501 0.120502" rpy="0 0 0"/>
|
||||
<parent link="link2_bottom"/>
|
||||
<child link="link2_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="link2_link3_joint">
|
||||
<origin xyz="0 0.0565 0.178003" rpy="0 0 0"/>
|
||||
<parent link="link2_top"/>
|
||||
<child link="link3_bottom"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
<joint type="continuous" name="link3_rot">
|
||||
<origin xyz="0 -0.055001 0.085501" rpy="0 0 0"/>
|
||||
<parent link="link3_bottom"/>
|
||||
<child link="link3_top"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" velocity="1.7453292519943"/>
|
||||
</joint>
|
||||
|
||||
<transmission name="trans_base_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="base_rot">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="base_rot_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_base_link1_joint">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="base_link1_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="base_link1_joint_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link1_link2_joint">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link1_link2_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="link1_link2_joint_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link2_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link2_rot">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="link2_rot_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link2_link3_joint">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link2_link3_joint">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="link2_link3_joint_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="trans_link3_rot">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="link3_rot">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="link3_rot_motor">
|
||||
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotNamespace>/iisy</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user