Skip to content

Commit e2b39b7

Browse files
Merge pull request #101 from AdarshKaran/humble
neo_simulation2 Humble branch updated with arm support and urdf files updated to modular xacros
2 parents 764eb07 + f19fbde commit e2b39b7

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

53 files changed

+2872
-1779
lines changed

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
This simulation package provides a quick and easy way to try out the autonomous mobile robots from Neobotix in ROS-2. It comes with the most commonly used configuration but is open for any kind of modification.
22

3-
Please find our documentations in https://neobotix-docs.de/ros/ros2/simulation.html
3+
Please find our documentations in https://neobotix-docs.de/ros/ros2/simulation_classic.html

components/arm/elite_arm.urdf.xacro

+37
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
<?xml version="1.0"?>
2+
<!-- This is the main URDF file for mpo_700-->
3+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="elite">
4+
5+
<!-- create arm from macro-->
6+
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
7+
8+
<xacro:arg name="arm_type" default="ec66"/>
9+
<xacro:arg name="use_gazebo" default="true"/>
10+
11+
<!--Elite arm parameters-->
12+
<xacro:arg name="tf_prefix" default="$(arg arm_type)"/>
13+
<xacro:arg name="joint_limit_params_file" default="$(find elite_description)/config/$(arg arm_type)/joint_limits.yaml"/>
14+
<xacro:arg name="joint_origin_params_file" default="$(find elite_description)/config/$(arg arm_type)/joint_origins.yaml"/>
15+
<xacro:arg name="link_inertials_params_file" default="$(find elite_description)/config/$(arg arm_type)/link_inertials.yaml"/>
16+
<xacro:arg name="initial_joint_positions_file" default="$(find elite_description)/config/$(arg arm_type)/initial_positions.yaml"/>
17+
18+
<!-- create arm -->
19+
<xacro:include filename="$(find elite_description)/urdf/macro/elite_macro.xacro" />
20+
<xacro:elite_robot
21+
name="$(arg arm_type)"
22+
tf_prefix="$(arg tf_prefix)"
23+
arm_parent="cabinet_link"
24+
joint_limits_parameters_file="$(arg joint_limit_params_file)"
25+
joint_origins_parameters_file="$(arg joint_origin_params_file)"
26+
link_inertials_parameters_file="$(arg link_inertials_params_file)"
27+
>
28+
<origin xyz="0.133 0.0 0.416" rpy="0.0 0.0 -1.5708" />
29+
</xacro:elite_robot>
30+
31+
<!-- If both Elite Arm and Simulation is used -->
32+
<xacro:if value="$(arg use_gazebo)">
33+
<xacro:include filename="$(find elite_description)/urdf/elite_gazebo_ros2_control.urdf.xacro" />
34+
</xacro:if>
35+
36+
</robot>
37+

components/arm/ur_arm.urdf.xacro

+61
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
<?xml version="1.0"?>
2+
<!-- This is the main URDF file for mpo_700-->
3+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="ur">
4+
5+
<!-- create arm from macro-->
6+
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
7+
8+
<xacro:arg name="arm_type" default="ur10"/>
9+
<xacro:arg name="use_gazebo" default="true"/>
10+
11+
<!-- UR arm parameters -->
12+
<xacro:arg name="tf_prefix" default="$(arg arm_type)" />
13+
<xacro:arg name="joint_limit_params" default="$(find ur_description)/config/$(arg arm_type)/joint_limits.yaml"/>
14+
<xacro:arg name="kinematics_params" default="$(find ur_description)/config/$(arg arm_type)/default_kinematics.yaml"/>
15+
<xacro:arg name="physical_params" default="$(find ur_description)/config/$(arg arm_type)/physical_parameters.yaml"/>
16+
<xacro:arg name="visual_params" default="$(find ur_description)/config/$(arg arm_type)/visual_parameters.yaml"/>
17+
<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>
18+
<xacro:arg name="safety_limits" default="false"/>
19+
<xacro:arg name="safety_pos_margin" default="0.15"/>
20+
<xacro:arg name="safety_k_position" default="20"/>
21+
<xacro:arg name="sim_gazebo" default="$(arg use_gazebo)" />
22+
<xacro:arg name="simulation_controllers" default="$(find neo_simulation2)/configs/ur_config/$(arg arm_type)/ur_controllers.yaml"/>
23+
<xacro:arg name="initial_positions_file" default="$(find neo_simulation2)/configs/ur_config/initial_joint_positions.yaml"/>
24+
25+
<!-- parse initial positions as a dictionary -->
26+
<xacro:property
27+
name="ur_initial_positions"
28+
value="${xacro.load_yaml('$(arg initial_positions_file)')}"
29+
/>
30+
31+
<xacro:ur_robot
32+
name="$(arg arm_type)"
33+
tf_prefix="$(arg tf_prefix)"
34+
parent="cabinet_link"
35+
joint_limits_parameters_file="$(arg joint_limit_params)"
36+
kinematics_parameters_file="$(arg kinematics_params)"
37+
physical_parameters_file="$(arg physical_params)"
38+
visual_parameters_file="$(arg visual_params)"
39+
safety_limits="$(arg safety_limits)"
40+
safety_pos_margin="$(arg safety_pos_margin)"
41+
safety_k_position="$(arg safety_k_position)"
42+
sim_gazebo="$(arg sim_gazebo)"
43+
initial_positions = "${ur_initial_positions}"
44+
>
45+
<!-- position robot in the world -->
46+
<origin xyz="0.133 0.0 0.416" rpy="0.0 0.0 -1.5708" />
47+
</xacro:ur_robot>
48+
49+
<!-- If both UR Arm and Simulation is used -->
50+
<xacro:if value="$(arg use_gazebo)">
51+
<gazebo reference="cabinet_link">
52+
</gazebo>
53+
<gazebo>
54+
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
55+
<parameters>$(arg simulation_controllers)</parameters>
56+
</plugin>
57+
</gazebo>
58+
</xacro:if>
59+
60+
</robot>
61+
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mp_500">
3+
4+
<!--Gazebo Diff Drive and Joint States Publisher plugin Macro-->
5+
<xacro:macro name="gazebo_diff_drive_plugin" params="
6+
update_rate
7+
joint_prefix
8+
wheel_separation
9+
wheel_diameter
10+
command_topic
11+
odometry_topic
12+
odom_frame
13+
base_frame
14+
max_wheel_torque
15+
max_acceleration
16+
">
17+
18+
<gazebo>
19+
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
20+
<!-- Replace camelCase elements with camel_case ones -->
21+
<update_rate>${update_rate}</update_rate>
22+
<left_joint>${joint_prefix}_left_joint</left_joint>
23+
<right_joint>${joint_prefix}_right_joint</right_joint>
24+
<wheel_separation>${wheel_separation}</wheel_separation>
25+
<wheel_diameter>${wheel_diameter}</wheel_diameter>
26+
<publish_odom>true</publish_odom>
27+
<publish_odom_tf>true</publish_odom_tf>
28+
<publish_wheel_tf>true</publish_wheel_tf>
29+
<command_topic>${command_topic}</command_topic>
30+
31+
<odometry_topic>${odometry_topic}</odometry_topic>
32+
<odometry_frame>${odom_frame}</odometry_frame>
33+
<robot_base_frame>${base_frame}</robot_base_frame>
34+
35+
<!-- wheelTorque and wheelAcceleration now have max_ prefix -->
36+
<max_wheel_torque>${max_wheel_torque}</max_wheel_torque>
37+
<max_acceleration>${max_acceleration}</max_acceleration>
38+
</plugin>
39+
40+
<plugin name="joint_states" filename="libgazebo_ros_joint_state_publisher.so">
41+
<joint_name>${joint_prefix}_left_joint</joint_name>
42+
<joint_name>${joint_prefix}_right_joint</joint_name>
43+
</plugin>
44+
45+
</gazebo>
46+
</xacro:macro>
47+
48+
</robot>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mpo">
3+
4+
<xacro:macro name="gazebo_lidar_sensor" params="
5+
sensor_name
6+
link_name
7+
update_rate
8+
min_range
9+
max_range
10+
horizontal_samples
11+
min_angle
12+
max_angle
13+
noise_mean
14+
noise_stddev
15+
topic_name
16+
visualize='false'
17+
">
18+
19+
<gazebo reference="${link_name}">
20+
<sensor name="${sensor_name}" type="ray">
21+
<always_on>true</always_on>
22+
<pose>0 0 0 0 0 0</pose>
23+
<visualize>${visualize}</visualize>
24+
<update_rate>${update_rate}</update_rate>
25+
<ray>
26+
<scan>
27+
<horizontal>
28+
<samples>${horizontal_samples}</samples>
29+
<resolution>1</resolution>
30+
<min_angle>${min_angle}</min_angle>
31+
<max_angle>${max_angle}</max_angle>
32+
</horizontal>
33+
</scan>
34+
<range>
35+
<min>${min_range}</min>
36+
<max>${max_range}</max>
37+
<resolution>0.05</resolution>
38+
</range>
39+
<noise>
40+
<type>gaussian</type>
41+
<!-- Noise parameters based on published spec for Hokuyo laser
42+
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
43+
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
44+
reading. -->
45+
<mean>${noise_mean}</mean>
46+
<stddev>${noise_stddev}</stddev>
47+
</noise>
48+
</ray>
49+
<plugin filename="libgazebo_ros_ray_sensor.so" name="${sensor_name}_plugin">
50+
<ros>
51+
<argument>~/out:=${topic_name}</argument>
52+
</ros>
53+
<output_type>sensor_msgs/LaserScan</output_type>
54+
<frame_name>${link_name}</frame_name>
55+
</plugin>
56+
</sensor>
57+
</gazebo>
58+
</xacro:macro>
59+
60+
</robot>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mpo">
3+
4+
<!--Gazebo Object Controller Macro-->
5+
<xacro:macro name="gazebo_object_controller" params="
6+
odom_update_rate
7+
controller_update_rate
8+
odom_frame
9+
base_frame
10+
covariance_yaw
11+
">
12+
13+
<gazebo>
14+
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
15+
<commandTopic>cmd_vel</commandTopic>
16+
<odometryTopic>odom</odometryTopic>
17+
<robotNamespace><remapping>/tf:=tf</remapping></robotNamespace>
18+
<ros> <remapping>/tf:=tf</remapping> </ros>
19+
20+
<!-- Set odom publish rate -->
21+
<odometryRate>${odom_update_rate}</odometryRate>
22+
23+
<!-- Set control loop update rate -->
24+
<publish_rate>${controller_update_rate}</publish_rate>
25+
26+
<!-- Set if odom required -->
27+
<publish_odom>true</publish_odom>
28+
<publish_odom_tf>true</publish_odom_tf>
29+
30+
<!-- Frame IDs -->
31+
<odometryFrame>${odom_frame}</odometryFrame>
32+
<robotBaseFrame>${base_frame}</robotBaseFrame>
33+
34+
<!-- Set odom covariance -->
35+
<covariance_x>0.0001</covariance_x>
36+
<covariance_y>0.0001</covariance_y>
37+
<covariance_yaw>${covariance_yaw}</covariance_yaw>
38+
</plugin>
39+
</gazebo>
40+
</xacro:macro>
41+
42+
</robot>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mpo">
3+
4+
<!--WHEEL MACRO-->
5+
<xacro:macro name="cabinet" params="
6+
neo_robot_name
7+
parent_link
8+
inertial_rpy
9+
visual_rpy
10+
collision_rpy
11+
*origin
12+
model_scale
13+
">
14+
15+
<joint name="cabinet_joint" type="fixed">
16+
<xacro:insert_block name="origin"/>
17+
<joint_properties damping="1" friction="1"/>
18+
<parent link="${parent_link}"/>
19+
<child link="cabinet_link"/>
20+
</joint>
21+
22+
<link name="cabinet_link">
23+
<inertial>
24+
<mass value="10"/>
25+
<origin rpy="${inertial_rpy}" xyz="0 0 0"/>
26+
<inertia ixx="0.457072" ixy="0.0" ixz="0.0" iyy="0.23616" iyz="0.0" izz="0.686"/>
27+
</inertial>
28+
<visual>
29+
<origin rpy="${visual_rpy}" xyz="0 0 0"/>
30+
<geometry>
31+
<mesh filename="package://neo_simulation2/robots/${neo_robot_name}/meshes/cabin.dae" scale="${model_scale}"/>
32+
</geometry>
33+
</visual>
34+
<collision>
35+
<origin rpy="${collision_rpy}" xyz="0 0 0"/>
36+
<geometry>
37+
<mesh filename="package://neo_simulation2/robots/mpo_700/meshes/cabin.dae" scale="${model_scale}"/>
38+
</geometry>
39+
</collision>
40+
</link>
41+
</xacro:macro>
42+
43+
</robot>
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
shoulder_pan_joint: 1.5
2+
shoulder_lift_joint: -2.5
3+
elbow_joint: 2.0
4+
wrist_1_joint: 0.0
5+
wrist_2_joint: -1.5
6+
wrist_3_joint: 0.0

0 commit comments

Comments
 (0)