Skip to content

Commit

Permalink
Remove humanoid_league_misc and add caching to tts (#335)
Browse files Browse the repository at this point in the history
  • Loading branch information
jaagut authored Feb 4, 2024
2 parents bcbf959 + 2b48470 commit e553d29
Show file tree
Hide file tree
Showing 65 changed files with 132 additions and 188 deletions.
4 changes: 3 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -221,5 +221,7 @@ doku/*
/lib/

# Path to the protocol buffer definitions, which are a diffrerent repository and managed by vcstool
/humanoid_league_misc/humanoid_league_team_communication/humanoid_league_team_communication/RobocupProtocol
/bitbots_team_communication/bitbots_team_communication/RobocupProtocol
# Protobuf generated file
/bitbots_team_communication/bitbots_team_communication/robocup_extension_pb2.py

Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<group>
<include file="$(find-pkg-share system_monitor)/launch/system_monitor.launch"/>
<include file="$(find-pkg-share bitbots_buttons)/launch/buttons.launch"/>
<include file="$(find-pkg-share humanoid_league_speaker)/launch/speaker.launch"/>
<include file="$(find-pkg-share bitbots_tts)/launch/tts.launch"/>
<!--include file="$(find-pkg-share bitbots_ros_control)/launch/pressure_converter.launch"/-->
</group>

Expand Down
2 changes: 1 addition & 1 deletion bitbots_lowlevel/bitbots_ros_control/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<depend>controller_manager</depend>
<depend>dynamixel_workbench_toolbox</depend>
<depend>hardware_interface</depend>
<depend>humanoid_league_speaker</depend>
<depend>bitbots_tts</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>realtime_tools</depend>
Expand Down
2 changes: 1 addition & 1 deletion bitbots_misc/bitbots_bringup/launch/highlevel.launch
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

<!-- launch teamcom -->
<group if="$(var teamcom)">
<include file="$(find-pkg-share humanoid_league_team_communication)/launch/team_comm.launch">
<include file="$(find-pkg-share bitbots_team_communication)/launch/team_comm.launch">
<arg name="sim" value="$(var sim)"/>
</include>
</group>
Expand Down
5 changes: 1 addition & 4 deletions bitbots_misc/bitbots_bringup/launch/visualization.launch
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,7 @@
<node name="motor_goals_viz_helper" pkg="bitbots_utils" exec="motor_goals_viz_helper.py"/>

<!-- add some visualization tools -->
<include file="$(find-pkg-share humanoid_league_interactive_marker)/launch/interactive_marker.launch">
<arg name="rviz" value="false" />
</include>
<include file="$(find-pkg-share humanoid_league_team_communication)/launch/team_comm_test_marker.launch">
<include file="$(find-pkg-share bitbots_team_communication)/launch/team_comm_test_marker.launch">
<arg name="rviz" value="false" />
</include>
</launch>
2 changes: 1 addition & 1 deletion bitbots_misc/bitbots_containers/hlvs/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ ADD https://www.timeapi.io/api/Time/current/zone?timeZone=UTC /tmp/build-time
RUN cd src/bitbots_main && \
make pull-all && \
rm -rf lib/udp_bridge bitbots_misc/bitbots_containers \
humanoid_league_visualization dynamic_stack_decider/dynamic_stack_decider_visualization bitbots_lowlevel \
lib/dynamic_stack_decider/dynamic_stack_decider_visualization bitbots_lowlevel \
bitbots_wolfgang/wolfgang_pybullet_sim lib/DynamixelSDK lib/dynamixel-workbench \
bitbots_misc/bitbots_basler_camera lib/pylon-ros-camera && \
sed -i '/plotjuggler/d' bitbots_motion/bitbots_quintic_walk/package.xml && \
Expand Down
46 changes: 2 additions & 44 deletions bitbots_misc/bitbots_docs/docs/manual/testing/testing.rst
Original file line number Diff line number Diff line change
Expand Up @@ -59,47 +59,6 @@ Starting (starts)
The next step is to check if the package actually starts without crashing instantly with an obvious error.
A part of this is that a launch file exists.

Testing in Visualization (tested_viz)
----------------------------------------

The easiest real test if the software works is in visualization with fake data/commands and then to look at the output.
For this you can also use real data that was recorded in a rosbag.

For this, it is important to be aware of your own testing bias.
Humans tend to test their own software for exactly the use cases they had in mind during programming.
However it is important to explicitly check all possibilities.
This means especially to test for edge cases and on robustness, e.g., testing with wrong data and against other parts of the software stack that crash.
A good method for this is to let someone else test your software, someone who was not involved in the programming of it.

This method is essentially used to prevent errors from happening and less to see how well something works.
The tests in this stage can be done via multiple methods:

Input
^^^^^^^^^^^

1. ros2 topic pub
2. RViz interactive marker
1. Path planning: inbuilt Navigation goal in RViz
2. behavior: humanoid_league_interactive_marker
3. special test scripts:
1. walking: bitbots_teleop
2. behavior: sim_gamestate (in gamecontroller package)
4. rosbags

Output
^^^^^^^^^^^^

1. ros2 topic echo
2. RViz marker
1. Object detection: humanoid_league_rviz_marker
2. Walking: published its own markers
3. RViz robot model
1. you might need to make the joint commands into joint_state (bitbots_bringup motor_goals_viz_helper.py)
4. special visualization tools for rqt
1. DSD: dynamic_stack_decider_visualization
2. Object Detection: humanoid_league_relative_rqt
3. Vision: bitbots_vision_tools

Testing in Simulation
------------------------------------------------

Expand Down Expand Up @@ -139,8 +98,7 @@ Conclusion
1. Each package has to be tested on its own
1. compiles
2. starts
3. using visualization
4. using simulation
5. on the real robot
3. using simulation
4. on the real robot
2. test packages pairwise
3. test the complete stack (integration)
File renamed without changes.
File renamed without changes.
File renamed without changes.
6 changes: 6 additions & 0 deletions bitbots_misc/bitbots_tts/launch/tts.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<executable cmd="mimic3-server --preload-voice en_US/vctk_low --cache-dir $(env HOME)/.cache/mimic3/" name="mimic3-server" output="screen"/>
<node name="bitbots_tts" pkg="bitbots_tts" exec="tts">
<param from="$(find-pkg-share bitbots_tts)/config/tts_config.yaml"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>humanoid_league_speaker</name>
<name>bitbots_tts</name>
<version>2.0.0</version>
<description>The humanoid_league_speaker package provides an easy way to do audio speech output via espeak.
<description>The bitbots_tts package provides an easy way to do audio speech output via a text to speach engine.
Messages send to the /speak topic are queued and spoken in another thread depending on their priority.
This can be used for debug but also for inter robot communication with natural language.</description>

Expand Down
4 changes: 4 additions & 0 deletions bitbots_misc/bitbots_tts/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/bitbots_tts
[install]
install_scripts=$base/lib/bitbots_tts
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

from setuptools import find_packages, setup

package_name = "humanoid_league_speaker"
package_name = "bitbots_tts"

setup(
name=package_name,
Expand All @@ -19,7 +19,7 @@
scripts=["scripts/send_text.py"],
entry_points={
"console_scripts": [
"speaker = humanoid_league_speaker.speaker:main",
"tts = bitbots_tts.tts:main",
],
},
)
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from humanoid_league_speaker.speaker import speak
from bitbots_tts.tts import speak

from bitbots_hcm.hcm_dsd.decisions import AbstractHCMDecisionElement

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,11 @@

import rclpy
from ament_index_python import get_package_share_directory
from bitbots_tts.tts import speak
from bitbots_utils.utils import get_parameters_from_ros_yaml
from builtin_interfaces.msg import Time as TimeMsg
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
from dynamic_stack_decider.dsd import DSD
from humanoid_league_speaker.speaker import speak
from rcl_interfaces.msg import Parameter as ParameterMsg
from rclpy.duration import Duration
from rclpy.executors import MultiThreadedExecutor
Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_hcm/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<depend>bitbots_utils</depend>
<depend>dynamic_stack_decider</depend>
<depend>geometry_msgs</depend>
<depend>humanoid_league_speaker</depend>
<depend>bitbots_tts</depend>
<depend>pybind11-dev</depend>
<depend>python3-numpy</depend>
<depend>python3-transforms3d</depend>
Expand Down
2 changes: 1 addition & 1 deletion bitbots_motion/bitbots_hcm/scripts/pause.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
import rclpy
from humanoid_league_speaker.speaker import speak
from bitbots_tts.tts import speak
from rclpy.node import Node
from std_msgs.msg import Bool

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(humanoid_league_team_communication)
project(bitbots_team_communication)

find_package(ament_cmake REQUIRED)
find_package(ament_cmake_python REQUIRED)
Expand All @@ -16,18 +16,17 @@ find_package(bitbots_docs REQUIRED)
find_package(Protobuf REQUIRED)

protobuf_generate_python(
PROTO_PY
humanoid_league_team_communication/RobocupProtocol/robocup_extension.proto)
PROTO_PY bitbots_team_communication/RobocupProtocol/robocup_extension.proto)

add_custom_target(
humanoid_league_team_communication ALL
bitbots_team_communication ALL
DEPENDS ${PROTO_PY}
COMMENT "Generating protobuf")
add_custom_command(
TARGET humanoid_league_team_communication
TARGET bitbots_team_communication
POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy ${PROTO_PY}
${CMAKE_SOURCE_DIR}/humanoid_league_team_communication
${CMAKE_SOURCE_DIR}/bitbots_team_communication
COMMENT "Copying protobuf to source dir")

enable_bitbots_docs()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,19 +21,19 @@
from tf2_geometry_msgs import PointStamped, PoseStamped
from tf2_ros import Buffer, TransformException

import humanoid_league_team_communication.robocup_extension_pb2 as Proto # noqa: N812
import bitbots_team_communication.robocup_extension_pb2 as Proto # noqa: N812
from bitbots_msgs.msg import Strategy, TeamData
from humanoid_league_team_communication.communication import SocketCommunication
from humanoid_league_team_communication.converter.robocup_protocol_converter import RobocupProtocolConverter, TeamColor
from bitbots_team_communication.communication import SocketCommunication
from bitbots_team_communication.converter.robocup_protocol_converter import RobocupProtocolConverter, TeamColor


class HumanoidLeagueTeamCommunication:
class TeamCommunication:
def __init__(self):
self._package_path = get_package_share_directory("humanoid_league_team_communication")
self._package_path = get_package_share_directory("bitbots_team_communication")
self.node = Node("team_comm", automatically_declare_parameters_from_overrides=True)
self.logger = self.node.get_logger()

self.logger.info("Initializing humanoid_league_team_communication...")
self.logger.info("Initializing bitbots_team_communication...")
params_blackboard = get_parameters_from_other_node(
self.node, "parameter_blackboard", ["bot_id", "team_id", "team_color"]
)
Expand Down Expand Up @@ -240,7 +240,7 @@ def get_current_time(self) -> Time:

def main():
rclpy.init(args=None)
HumanoidLeagueTeamCommunication()
TeamCommunication()


if __name__ == "__main__":
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
from geometry_msgs.msg import PoseWithCovariance
from numpy import double

import humanoid_league_team_communication.robocup_extension_pb2 as Proto # noqa: N812
import bitbots_team_communication.robocup_extension_pb2 as Proto # noqa: N812
from bitbots_msgs.msg import RobotRelative, RobotRelativeArray, TeamData


Expand All @@ -22,8 +22,6 @@ def convert(self, message: Proto.Message, team_data: TeamData) -> TeamData:
team_data.robot_position = self.convert_robot_pose(message.current_pose)
team_data.ball_absolute = self.convert_ball_pose(message.ball)

# @TODO: change TeamData field/type to robots
# see: https://github.com/bit-bots/humanoid_league_misc/issues/125
team_data.robots = self.convert_robots(message.others, message.other_robot_confidence)
team_data.robots.header = team_data.header

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@

from soccer_vision_attribute_msgs.msg import Robot as RobotAttributes

import humanoid_league_team_communication.robocup_extension_pb2 as Proto # noqa: N812
import bitbots_team_communication.robocup_extension_pb2 as Proto # noqa: N812
from bitbots_msgs.msg import RobotRelative, Strategy
from humanoid_league_team_communication.converter.message_to_team_data_converter import MessageToTeamDataConverter
from humanoid_league_team_communication.converter.state_to_message_converter import StateToMessageConverter
from bitbots_team_communication.converter.message_to_team_data_converter import MessageToTeamDataConverter
from bitbots_team_communication.converter.state_to_message_converter import StateToMessageConverter


class TeamColor(IntEnum):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from rclpy.time import Time
from soccer_vision_3d_msgs.msg import Robot, RobotArray

import humanoid_league_team_communication.robocup_extension_pb2 as Proto # noqa: N812
import bitbots_team_communication.robocup_extension_pb2 as Proto # noqa: N812
from bitbots_msgs.msg import Strategy


Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<!-- Get launch params-->
<arg name="sim" default="false" description="true: activates simulation time" />

<node pkg="humanoid_league_team_communication" exec="team_comm.py" output="screen">
<param from="$(find-pkg-share humanoid_league_team_communication)/config/team_communication_config.yaml"/>
<node pkg="bitbots_team_communication" exec="team_comm.py" output="screen">
<param from="$(find-pkg-share bitbots_team_communication)/config/team_communication_config.yaml"/>
<param name="use_sim_time" value="$(var sim)" />
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
<!-- load the global parameters -->
<include file="$(find-pkg-share bitbots_utils)/launch/parameter_blackboard.launch" />

<node pkg="humanoid_league_team_communication" exec="team_comm.py" output="screen">
<param from="$(find-pkg-share humanoid_league_team_communication)/config/team_communication_config.yaml"/>
<node pkg="bitbots_team_communication" exec="team_comm.py" output="screen">
<param from="$(find-pkg-share bitbots_team_communication)/config/team_communication_config.yaml"/>
<param name="use_sim_time" value="$(var sim)" />
</node>
</launch>
11 changes: 11 additions & 0 deletions bitbots_team_communication/launch/team_comm_test_marker.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<launch>
<arg name="rviz" default="true"/>

<group if="$(var rviz)">
<node pkg="rviz2" exec="rviz2" output="screen" args="-d $(find-pkg-share bitbots_team_communication)/config/team_comm_marker.rviz">
</node>
</group>
<node name="team_comm_test_marker" pkg="bitbots_team_communication" exec="team_comm_test_marker.py" output="screen">
<param from="$(find-pkg-share bitbots_team_communication)/config/team_communication_config.yaml" />
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>humanoid_league_team_communication</name>
<name>bitbots_team_communication</name>
<version>3.0.0</version>
<description>The humanoid_league_team_communication package provides a ROS wrapper for the Protobuf RoboCup protocol.
<description>The bitbots_team_communication package provides a ROS wrapper for the Protobuf RoboCup protocol.
This is the standard communication protocol developed by the NUbots. </description>

<maintainer email="[email protected]">Joern Griepenburg</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ def generate_string(self, data: TeamData):
lines.append(f" y: {round(data.ball_absolute.pose.position.y, 3):<4}")
lines.append(f" x_cov: {round(data.ball_absolute.covariance[0], 3):<4}")
lines.append(f" y_cov: {round(data.ball_absolute.covariance[7], 3):<4}")
lines.append(f"Obstacles found: {len(data.obstacles.obstacles)}")
lines.append(f"Robots found: {len(data.robots.robots)}")
lines.append("Strategy")
lines.append(f" Role: {self.roles[data.strategy.role]:<9}")
lines.append(f" Action: {self.actions[data.strategy.action]:<15}")
Expand Down
7 changes: 7 additions & 0 deletions bitbots_team_communication/scripts/team_comm.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#!/usr/bin/env python3

import sys

from bitbots_team_communication.bitbots_team_communication import main

sys.exit(main())
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import rclpy
from game_controller_hl_interfaces.msg import GameState
from geometry_msgs.msg import Point, Pose, PoseWithCovariance, PoseWithCovarianceStamped, Quaternion, TransformStamped
from rclpy.qos import QoSDurabilityPolicy, QoSProfile
from soccer_vision_3d_msgs.msg import Robot, RobotArray
from soccer_vision_attribute_msgs.msg import Robot as RobotAttributes
from tf2_ros import StaticTransformBroadcaster
Expand Down Expand Up @@ -51,7 +52,9 @@ def base_footprint_transform():
node = rclpy.create_node("test_team_comm")
tf_static_broadcaster = StaticTransformBroadcaster(node)

gamestate_pub = node.create_publisher(GameState, "gamestate", 1)
gamestate_pub = node.create_publisher(
GameState, "gamestate", qos_profile=QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL)
)
strategy_pub = node.create_publisher(Strategy, "strategy", 1)
ball_pub = node.create_publisher(PoseWithCovarianceStamped, "ball_position_relative_filtered", 1)
position_pub = node.create_publisher(PoseWithCovarianceStamped, "pose_with_covariance", 1)
Expand Down
Loading

0 comments on commit e553d29

Please sign in to comment.