Gazebo simulation package for VSS robots
This package contains configuration data, 3D models and launch files
@@ -15,6 +15,7 @@ for vss_robot robot
roslaunch
robot_state_publisher
velocity_controllers
+ effort_controllers
rviz
joint_state_publisher
gazebo
diff --git a/scripts/keyboard_node.py b/scripts/keyboard_node.py
index af6f2f9..1ca7816 100755
--- a/scripts/keyboard_node.py
+++ b/scripts/keyboard_node.py
@@ -30,7 +30,7 @@
ROBOTS = 3
# Namespace dos tópicos que iremos publicar
-DEFAULT_NAMESPACE = "/robot_{}"
+DEFAULT_NAMESPACE = "/robot{}"
DEFAULT_DEBUG = False
@@ -39,6 +39,7 @@
WHEEL_RADIUS = 0.030 # m
ANG_VEL = LIN_VEL/WHEEL_RADIUS # rad/s
+ANG_VEL = 0.1078 # Nm
# Os comandos vão de -126 até 126 de modo que os bytes 0xFE e 0xFF
# nunca são utilizados
@@ -46,7 +47,7 @@
def getNamespace(number):
- return DEFAULT_NAMESPACE.format(number)
+ return DEFAULT_NAMESPACE.format(number+1)
def drawConsole(win, font, console):
diff --git a/scripts/velocity_proxy.py b/scripts/velocity_proxy.py
index 563c48e..f2759e0 100755
--- a/scripts/velocity_proxy.py
+++ b/scripts/velocity_proxy.py
@@ -2,7 +2,7 @@
# coding=utf-8
"""
File:
- velocity_conversion.py
+ velocity_proxy.py
Description:
Simple python routine to convert velocity message
diff --git a/scripts/vision_proxy.py b/scripts/vision_proxy.py
index ed7eb5b..a84c3a9 100755
--- a/scripts/vision_proxy.py
+++ b/scripts/vision_proxy.py
@@ -6,25 +6,61 @@
Description:
Simple python routine to separe the information published
- from gazebo into several topics
+ from gazebo into several topics.
+ We remove any "vss_" prefixes when creating the topic name
+
+ Params:
+ - /vision/precision
+ - /vision/std_dev
+
+ Topics:
+ - /vision/ball
+ - /vision/robot1
+ - /vision/robot2
+ - /vision/robot3
+ - /vision/foe1
+ - /vision/foe2
+ - /vision/foe3
"""
import rospy
+import random
+from math import sin, cos, pi
from std_msgs.msg import String
from gazebo_msgs.msg import ModelStates, ModelState
-MODELS = ["ball",
- "robot1",
- "robot2",
- "robot3",
- "foe1",
- "foe2",
- "foe3"]
+# We take out every "vss_" prefix from our models
+MODELS_NAMES = ["vss_ball",
+ "robot1",
+ "robot2",
+ "robot3",
+ "foe1",
+ "foe2",
+ "foe3"]
pubs = {}
-for model in MODELS:
- pubs[model] = rospy.Publisher("/vision/" + model, ModelState, queue_size=1)
+
+def clean_model_name(model):
+ if model.split("_")[0] == "vss":
+ model = "_".join(model.split("_")[1:])
+ return model
+
+for model in MODELS_NAMES:
+ pubs[model] = rospy.Publisher("/vision/" + clean_model_name(model),
+ ModelState, queue_size=1)
+
+
+def apply_noise(data):
+ std_dev = rospy.get_param("/vision/std_dev", 0)
+
+ theta = random.uniform(0, pi)
+ radius = random.gauss(0, std_dev)
+
+ data.position.x += radius*cos(theta)
+ data.position.y += radius*sin(theta)
+
+ return data
def callback(data):
@@ -36,9 +72,9 @@ def callback(data):
"""
rospy.loginfo(rospy.get_caller_id() + " I heard %s", data.name)
for i, model in enumerate(data.name):
- if model in MODELS:
+ if model in MODELS_NAMES:
msg = ModelState(model_name=model,
- pose=data.pose[i],
+ pose=apply_noise(data.pose[i]),
twist=data.twist[i])
pubs[model].publish(msg)
diff --git a/urdf/hat_colors.xacro b/urdf/hat_colors.xacro
new file mode 100644
index 0000000..8197aa9
--- /dev/null
+++ b/urdf/hat_colors.xacro
@@ -0,0 +1,28 @@
+
+
+
+
+
+
+
+ Gazebo/Black
+
+
+
+ ${team_color}
+
+
+
+ ${robot_color}
+
+
+
+ ${robot_color}
+
+
+
+ ${robot_color}
+
+
+
+
\ No newline at end of file
diff --git a/urdf/motor.xacro b/urdf/motor.xacro
index 59b0fa8..fb343c1 100644
--- a/urdf/motor.xacro
+++ b/urdf/motor.xacro
@@ -19,9 +19,7 @@
-
-
- hardware_interface/VelocityJointInterface
+ hardware_interface/EffortJointInterface
diff --git a/urdf/vss_robot.gazebo b/urdf/vss_robot.gazebo
index 8864251..69427a8 100644
--- a/urdf/vss_robot.gazebo
+++ b/urdf/vss_robot.gazebo
@@ -7,6 +7,11 @@
+
+
+
+
+
@@ -42,7 +47,12 @@
- /robot$(arg robot_number)
+
+ /robot$(arg robot_number)
+
+
+ /foe$(arg robot_number)
+
\ No newline at end of file
diff --git a/urdf/vss_robot.urdf b/urdf/vss_robot.urdf
index 35079f5..84b977c 100755
--- a/urdf/vss_robot.urdf
+++ b/urdf/vss_robot.urdf
@@ -87,6 +87,11 @@
+
+
+
+
+
@@ -140,6 +145,11 @@
+
+
+
+
+
diff --git a/urdf/vss_team.xacro b/urdf/vss_team.xacro
index 8ad0cb2..921d6db 100644
--- a/urdf/vss_team.xacro
+++ b/urdf/vss_team.xacro
@@ -5,23 +5,11 @@
+
-
-
- Gazebo/Black
-
-
-
- Gazebo/Black
-
-
-
+
-
- Gazebo/Yellow
-
-
Gazebo/White
@@ -35,50 +23,23 @@
-
-
-
- Gazebo/Black
-
-
-
- Gazebo/Purple
-
-
-
-
-
-
- Gazebo/Black
-
-
-
- Gazebo/Red
-
-
+
+
+
-
- Gazebo/Black
-
-
-
- Gazebo/Green
-
-
+
+
-
+
+
-
- Gazebo/Blue
-
-
Gazebo/Grey
@@ -92,42 +53,18 @@
-
-
-
- Gazebo/Black
-
-
-
- Gazebo/SkyBlue
-
-
-
-
-
-
- Gazebo/Black
-
-
-
- Gazebo/Turquoise
-
-
+
+
+
-
- Gazebo/Black
-
-
-
- Gazebo/Indigo
-
-
+
+
-
+
diff --git a/worlds/vss_field.world b/worlds/vss_field.world
index 24b5be2..88fdf33 100644
--- a/worlds/vss_field.world
+++ b/worlds/vss_field.world
@@ -10,13 +10,13 @@
- model://sun
+ model://my_sun
-
+
@@ -26,7 +26,7 @@
0 0 0.040 0 0 0
- model://golf_ball
+ model://vss_ball
diff --git a/worlds/vss_field_top.world b/worlds/vss_field_top.world
index 34482f9..e09213f 100644
--- a/worlds/vss_field_top.world
+++ b/worlds/vss_field_top.world
@@ -10,14 +10,13 @@
- 10.0 0 10.0 0 0 0
- model://sun
+ model://my_sun
-
+
@@ -27,7 +26,7 @@
0 0 0.040 0 0 0
- model://golf_ball
+ model://vss_ball