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

Mecanum wheels demo #683

Merged
merged 18 commits into from
Mar 24, 2021
Merged
Show file tree
Hide file tree
Changes from 14 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
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ set(IGN_RENDERING_VER ${ignition-rendering5_VERSION_MAJOR})

#--------------------------------------
# Find ignition-math
ign_find_package(ignition-math6 REQUIRED COMPONENTS eigen3 VERSION 6.6)
ign_find_package(ignition-math6 REQUIRED COMPONENTS eigen3 VERSION 6.8)
set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR})

#--------------------------------------
Expand Down
362 changes: 362 additions & 0 deletions examples/worlds/diff_drive_mecanum.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,362 @@
<?xml version="1.0" ?>
<!--
Ignition Gazebo skid steer differential drive plugin demo
chapulina marked this conversation as resolved.
Show resolved Hide resolved

Try sending commands:

ign topic -t "/model/vehicle_blue/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 0.5}, angular: {z: 0.05}"

Listen to odometry:

ign topic -e -t /model/vehicle_blue/odometry

-->
<sdf version="1.6">
<world name="diff_drive">

<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>50</mu>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name='vehicle_blue' xmlns:gazebo="http://gazebosim.org/schema">
chapulina marked this conversation as resolved.
Show resolved Hide resolved
<pose>0 2 0.325 0 -0 0</pose>

<link name='chassis'>
<pose>-0.151427 -0 0.175 0 -0 0</pose>
<inertial>
<mass>1.14395</mass>
<inertia>
<ixx>0.126164</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.416519</iyy>
<iyz>0</iyz>
<izz>0.481014</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>2.01142 1 0.568726</size>
</box>
</geometry>
<material>
<ambient>0.5 0.5 1.0 1</ambient>
<diffuse>0.5 0.5 1.0 1</diffuse>
<specular>0.0 0.0 1.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>2.01142 1 0.568726</size>
</box>
</geometry>
</collision>
</link>

<link name='front_left_wheel'>
<pose>0.554283 0.625029 -0.025 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<!--sphere>
<radius>0.3</radius>
</sphere-->
<box><size>0.6 0.6 0.6</size></box>
chapulina marked this conversation as resolved.
Show resolved Hide resolved
<!--mesh>
<uri>https://raw.githubusercontent.com/robomaster-oss/rmoss_ign_resources/main/models/rmua19_standard_robot/meshes/wheel_left.dae</uri>
<scale>2.4 2.4 2.4</scale>
</mesh-->
</geometry>
<material>
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.2 0.2 0.2 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1 ignition:expressed_in="chassis">1 -1 0</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>

<link name='rear_left_wheel'>
<pose>-0.957138 0.625029 -0.025 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<!--sphere>
<radius>0.3</radius>
</sphere-->
<box><size>0.6 0.6 0.6</size></box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.2 0.2 0.2 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1 ignition:expressed_in="chassis">1 1 0</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>

<link name='front_right_wheel'>
<pose>0.554282 -0.625029 -0.025 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<!--sphere>
<radius>0.3</radius>
</sphere-->
<box><size>0.6 0.6 0.6</size></box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.2 0.2 0.2 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1 ignition:expressed_in="chassis">1 1 0</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>

<link name='rear_right_wheel'>
<pose>-0.957138 -0.625029 -0.025 -1.5707 0 0</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<!--sphere>
<radius>0.3</radius>
</sphere-->
<box><size>0.6 0.6 0.6</size></box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.2 0.2 0.2 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.3</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1 ignition:expressed_in="chassis">1 -1 0</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>


<joint name='front_left_wheel_joint' type='revolute'>
<parent>chassis</parent>
<child>front_left_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>

<joint name='front_right_wheel_joint' type='revolute'>
<parent>chassis</parent>
<child>front_right_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>

<joint name='rear_left_wheel_joint' type='revolute'>
<parent>chassis</parent>
<child>rear_left_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>

<joint name='rear_right_wheel_joint' type='revolute'>
<parent>chassis</parent>
<child>rear_right_wheel</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>

<plugin
filename="ignition-gazebo-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<wheel_separation>1.25</wheel_separation>
<wheel_radius>0.3</wheel_radius>
</plugin>

</model>

</world>
</sdf>
Loading