Skip to content
This repository was archived by the owner on Jan 28, 2023. It is now read-only.

Commit dc21b99

Browse files
committed
imprement vision_wrapper
1 parent 83f288e commit dc21b99

12 files changed

Lines changed: 442 additions & 0 deletions

File tree

consai2r2_msgs/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,8 @@ set(msg_files
2929
"msg/DetectionRobot.msg"
3030
"msg/DetectionFrame.msg"
3131
"msg/VisionDetections.msg"
32+
"msg/RobotInfo.msg"
33+
"msg/BallInfo.msg"
3234
"msg/RobotCommand.msg"
3335
"msg/RobotCommands.msg"
3436
)

consai2r2_msgs/msg/BallInfo.msg

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
# ball information for consai2_game
2+
3+
geometry_msgs/Pose2D pose
4+
geometry_msgs/Pose2D velocity
5+
geometry_msgs/Twist velocity_twist
6+
bool detected
7+
builtin_interfaces/Time detection_stamp
8+
9+
geometry_msgs/Pose2D last_detection_pose
10+
bool disappeared

consai2r2_msgs/msg/RobotInfo.msg

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
# robot information for consai2_game
2+
3+
# robot id
4+
uint8 robot_id
5+
6+
# Robot 2D pose
7+
# This field will be replaced to geometry_msgs/Pose
8+
geometry_msgs/Pose2D pose
9+
10+
# Robot Velocity
11+
# [Deprecated] This field will be removed.
12+
geometry_msgs/Pose2D velocity
13+
14+
# Robot Velocity
15+
geometry_msgs/Twist velocity_twist
16+
17+
# If robot is detected by vision in this frame, this field is set to true
18+
bool detected
19+
20+
# Latest vision detection time
21+
# [Deprecated] This field will be removed.
22+
builtin_interfaces/Time detection_stamp
23+
24+
# Latest detected pose.
25+
# This field is NOT filtered. This is a raw vision value.
26+
geometry_msgs/Pose2D last_detection_pose
27+
28+
# If a robot disappear from field, this field is set to true
29+
bool disappeared

consai2r2_vision_wrapper/consai2r2_vision_wrapper/__init__.py

Whitespace-only changes.
Lines changed: 268 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,268 @@
1+
# Copyright (c) 2019 SSL-Roots
2+
#
3+
# Permission is hereby granted, free of charge, to any person obtaining a copy
4+
# of this software and associated documentation files (the "Software"), to deal
5+
# in the Software without restriction, including without limitation the rights
6+
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
7+
# copies of the Software, and to permit persons to whom the Software is
8+
# furnished to do so, subject to the following conditions:
9+
#
10+
# The above copyright notice and this permission notice shall be included in
11+
# all copies or substantial portions of the Software.
12+
#
13+
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14+
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15+
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
16+
# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17+
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
18+
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
19+
# THE SOFTWARE.
20+
21+
import math
22+
23+
from consai2r2_description import consai2r2_parameters
24+
25+
from consai2r2_msgs.msg import BallInfo, RobotInfo, VisionDetections
26+
from geometry_msgs.msg import Pose2D
27+
28+
import rclpy
29+
from rclpy.clock import Clock, ClockType
30+
from rclpy.node import Node
31+
from rclpy.time import Time
32+
33+
34+
class VisionWrapper(Node):
35+
36+
def __init__(self):
37+
super().__init__('consai2r2_vision_wrapper')
38+
39+
QUEUE_SIZE = 10
40+
self._DISAPPERED_TIME_THRESH = 3.0
41+
self._PUBLISH_ROBOT = {'blue': False, 'yellow': False}
42+
43+
self.declare_parameter('publish_ball', True)
44+
self.declare_parameter('publish_blue', True)
45+
self.declare_parameter('publish_yellow', True)
46+
47+
common_params = consai2r2_parameters(self)
48+
self._OUR_COLOR = common_params.our_color
49+
self._MAX_ID = common_params.max_id
50+
51+
self._PUBLISH_BALL = self.get_parameter('publish_ball').value
52+
self._PUBLISH_ROBOT['blue'] = self.get_parameter('publish_blue').value
53+
self._PUBLISH_ROBOT['yellow'] = self.get_parameter(
54+
'publish_yellow').value
55+
56+
self._pub_ball_info = None
57+
self._ball_info = BallInfo()
58+
59+
if self._PUBLISH_BALL:
60+
self._pub_ball_info = self.create_publisher(
61+
BallInfo, '~/ball_info', QUEUE_SIZE)
62+
63+
self._robot_info = {'blue': [], 'yellow': []}
64+
self._pubs_robot_info = {'blue': [], 'yellow': []}
65+
66+
for robot_id in range(self._MAX_ID + 1):
67+
# 末尾に16進数の文字列をつける
68+
topic_id = hex(robot_id)[2:]
69+
70+
self._robot_info['blue'].append(RobotInfo())
71+
self._robot_info['yellow'].append(RobotInfo())
72+
73+
if self._PUBLISH_ROBOT['blue']:
74+
topic_name = '~/robot_info_blue_' + topic_id
75+
pub_robot_info = self.create_publisher(
76+
RobotInfo, topic_name, QUEUE_SIZE)
77+
self._pubs_robot_info['blue'].append(pub_robot_info)
78+
79+
if self._PUBLISH_ROBOT['yellow']:
80+
topic_name = '~/robot_info_yellow_' + topic_id
81+
pub_robot_info = self.create_publisher(
82+
RobotInfo, topic_name, QUEUE_SIZE)
83+
self._pubs_robot_info['yellow'].append(pub_robot_info)
84+
85+
self.create_subscription(
86+
VisionDetections, 'consai2r2_vision_receiver/raw_vision_detections',
87+
self._callback_detections, 1)
88+
89+
def _callback_detections(self, msg):
90+
# Visionのデータからロボットとボールの位置を抽出する
91+
92+
time_stamp = msg.header.stamp
93+
94+
detection_balls = []
95+
detection_blues = []
96+
detection_yellows = []
97+
for frame in msg.frames:
98+
for ball in frame.balls:
99+
detection_balls.append(ball)
100+
101+
for blue in frame.robots_blue:
102+
detection_blues.append(blue)
103+
104+
for yellow in frame.robots_yellow:
105+
detection_yellows.append(yellow)
106+
107+
self._extract_ball_pose(detection_balls, time_stamp)
108+
self._extract_robot_pose('blue', detection_blues, time_stamp)
109+
self._extract_robot_pose('yellow', detection_yellows, time_stamp)
110+
111+
def _extract_ball_pose(self, detection_balls, time_stamp):
112+
# ボール座標を抽出する
113+
# ボール座標が複数ある場合は、平均値を座標とする
114+
if detection_balls:
115+
average_pose = self._average_pose(detection_balls)
116+
velocity = self._velocity(
117+
self._ball_info.pose, average_pose, self._ball_info.detection_stamp, time_stamp)
118+
119+
self._ball_info.pose = average_pose
120+
self._ball_info.last_detection_pose = average_pose
121+
self._ball_info.velocity = velocity
122+
self._ball_info.detected = True
123+
self._ball_info.detection_stamp = time_stamp
124+
self._ball_info.disappeared = False
125+
else:
126+
self._ball_info.detected = False
127+
128+
if self._ball_info.disappeared is False:
129+
# 座標を受け取らなかった場合は、速度を用いて線形予測する
130+
131+
diff_time_stamp = Clock(clock_type=ClockType.ROS_TIME).now(
132+
) - Time.from_msg(self._ball_info.detection_stamp)
133+
diff_time_secs = diff_time_stamp.nanoseconds / 1000000000
134+
135+
self._ball_info.pose = self._estimate(
136+
self._ball_info.last_detection_pose,
137+
self._ball_info.velocity, diff_time_secs)
138+
139+
# 一定時間、座標を受け取らなかったら消滅判定にする
140+
if diff_time_secs > self._DISAPPERED_TIME_THRESH:
141+
self._ball_info.disappeared = True
142+
143+
if self._PUBLISH_BALL:
144+
self._pub_ball_info.publish(self._ball_info)
145+
146+
def _extract_robot_pose(self, color, detection_robots, time_stamp):
147+
# ロボット姿勢を抽出する
148+
# ロボット姿勢が複数ある場合は、平均値を姿勢とする
149+
detections = [[] for i in range(len(self._robot_info[color]))]
150+
151+
# ID毎のリストに分ける
152+
for robot in detection_robots:
153+
robot_id = robot.robot_id
154+
detections[robot_id].append(robot)
155+
156+
for robot_id, robots in enumerate(detections):
157+
if robots:
158+
average_pose = self._average_pose(robots)
159+
velocity = self._velocity(
160+
self._robot_info[color][robot_id].pose, average_pose,
161+
self._robot_info[color][robot_id].detection_stamp, time_stamp)
162+
163+
self._robot_info[color][robot_id].robot_id = robot_id
164+
self._robot_info[color][robot_id].pose = average_pose
165+
self._robot_info[color][robot_id].last_detection_pose = average_pose
166+
self._robot_info[color][robot_id].velocity = velocity
167+
self._robot_info[color][robot_id].detected = True
168+
self._robot_info[color][robot_id].detection_stamp = time_stamp
169+
self._robot_info[color][robot_id].disappeared = False
170+
else:
171+
self._robot_info[color][robot_id].detected = False
172+
self._robot_info[color][robot_id].robot_id = robot_id
173+
174+
# 座標を受け取らなかった場合は、速度を用いて線形予測する
175+
if self._robot_info[color][robot_id].disappeared is False:
176+
duration = Clock(clock_type=ClockType.ROS_TIME).now() - \
177+
Time.from_msg(self._robot_info[color][robot_id].detection_stamp)
178+
diff_time_secs = duration.nanoseconds / 1000000000
179+
180+
self._robot_info[color][robot_id].pose = self._estimate(
181+
self._robot_info[color][robot_id].last_detection_pose,
182+
self._robot_info[color][robot_id].velocity, diff_time_secs)
183+
184+
# 一定時間、座標を受け取らなかったら消滅判定にする
185+
if diff_time_secs > self._DISAPPERED_TIME_THRESH:
186+
self._robot_info[color][robot_id].disappeared = True
187+
188+
if self._PUBLISH_ROBOT[color]:
189+
for robot_id in range(len(self._pubs_robot_info[color])):
190+
self._pubs_robot_info[color][robot_id].publish(
191+
self._robot_info[color][robot_id])
192+
193+
def _average_pose(self, detections):
194+
# 姿勢の平均値を求める
195+
# 角度をpi ~ -piに収めるため、極座標系に角度を変換している
196+
197+
sum_pose = Pose2D()
198+
detection_num = float(len(detections))
199+
200+
# 角度計算用
201+
sum_x = 0.0
202+
sum_y = 0.0
203+
for detection in detections:
204+
sum_pose.x += detection.pose.x
205+
sum_pose.y += detection.pose.y
206+
sum_x += math.cos(detection.pose.theta)
207+
sum_y += math.sin(detection.pose.theta)
208+
sum_pose.x = sum_pose.x / detection_num
209+
sum_pose.y = sum_pose.y / detection_num
210+
sum_pose.theta = math.fmod(math.atan2(sum_y, sum_x), math.pi)
211+
212+
return sum_pose
213+
214+
def _velocity(self, prev_pose, current_pose, prev_stamp, current_stamp):
215+
# 姿勢の差分から速度を求める
216+
217+
velocity = Pose2D()
218+
diff_time_stamp = Time.from_msg(
219+
current_stamp) - Time.from_msg(prev_stamp)
220+
diff_time_secs = diff_time_stamp.nanoseconds / 1000000000
221+
222+
if diff_time_secs > 0:
223+
diff_pose = Pose2D()
224+
diff_pose.x = current_pose.x - prev_pose.x
225+
diff_pose.y = current_pose.y - prev_pose.y
226+
diff_pose.theta = self._angle_normalize(
227+
current_pose.theta - prev_pose.theta)
228+
229+
velocity.x = diff_pose.x / diff_time_secs
230+
velocity.y = diff_pose.y / diff_time_secs
231+
velocity.theta = diff_pose.theta / diff_time_secs
232+
233+
return velocity
234+
235+
def _estimate(self, pose, velocity, diff_time_secs):
236+
# 速度と時間をもとに、姿勢を線形予測する
237+
238+
estimated_pose = Pose2D()
239+
240+
estimated_pose.x = pose.x + velocity.x * diff_time_secs
241+
estimated_pose.y = pose.y + velocity.y * diff_time_secs
242+
estimated_pose.theta = pose.theta + velocity.theta * diff_time_secs
243+
244+
return estimated_pose
245+
246+
def _angle_normalize(self, angle):
247+
# 角度をpi ~ -piの範囲に変換する
248+
while angle > math.pi:
249+
angle -= 2*math.pi
250+
251+
while angle < -math.pi:
252+
angle += 2*math.pi
253+
254+
return angle
255+
256+
257+
def main(args=None):
258+
rclpy.init(args=args)
259+
wrapper = VisionWrapper()
260+
261+
rclpy.spin(wrapper)
262+
263+
wrapper.destroy_node()
264+
rclpy.shutdown()
265+
266+
267+
if __name__ == '__main__':
268+
main()
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>consai2r2_vision_wrapper</name>
5+
<version>0.0.0</version>
6+
<description>Vision Wrapper</description>
7+
<maintainer email="macakasit@gmail.com">akshota</maintainer>
8+
<license>MIT</license>
9+
10+
<exec_depend>rclpy</exec_depend>
11+
<exec_depend>consai2r2_msgs</exec_depend>
12+
<exec_depend>consai2r2_receiver</exec_depend>
13+
<exec_depend>consai2r2_description</exec_depend>
14+
15+
<!-- These test dependencies are optional
16+
Their purpose is to make sure that the code passes the linters -->
17+
<test_depend>ament_copyright</test_depend>
18+
<test_depend>ament_flake8</test_depend>
19+
<test_depend>ament_pep257</test_depend>
20+
<test_depend>python3-pytest</test_depend>
21+
22+
<export>
23+
<build_type>ament_python</build_type>
24+
</export>
25+
</package>

consai2r2_vision_wrapper/resource/consai2r2_vision_wrapper

Whitespace-only changes.

consai2r2_vision_wrapper/setup.cfg

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
[develop]
2+
script-dir=$base/lib/consai2r2_vision_wrapper
3+
[install]
4+
install-scripts=$base/lib/consai2r2_vision_wrapper

consai2r2_vision_wrapper/setup.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
from setuptools import setup
2+
3+
package_name = 'consai2r2_vision_wrapper'
4+
5+
setup(
6+
name=package_name,
7+
version='0.0.0',
8+
packages=[package_name],
9+
data_files=[
10+
('share/ament_index/resource_index/packages',
11+
['resource/' + package_name]),
12+
('share/' + package_name, ['package.xml']),
13+
],
14+
install_requires=['setuptools'],
15+
zip_safe=True,
16+
author='akshota',
17+
author_email='macakasit@gmail.com',
18+
maintainer='akshota',
19+
maintainer_email='macakasit@gmail.com',
20+
keywords=['ROS'],
21+
classifiers=[
22+
'Intended Audience :: Developers',
23+
'License :: OSI Approved :: MIT License',
24+
'Programming Language :: Python',
25+
'Topic :: Software Development',
26+
],
27+
description='Convert raw vision message to AI-friendly message',
28+
license='MIT License',
29+
tests_require=['pytest'],
30+
entry_points={
31+
'console_scripts': [
32+
'vision_wrapper = consai2r2_vision_wrapper.vision_wrapper:main',
33+
],
34+
},
35+
)

0 commit comments

Comments
 (0)