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

Update publish_test_obstacles.py #3

Merged
merged 1 commit into from
Jun 14, 2021
Merged
Changes from all 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
82 changes: 58 additions & 24 deletions scripts/publish_test_obstacles.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,41 +17,75 @@ def publish_obstacle_msg():
obstacle_msg.header.stamp = rospy.Time.now()
obstacle_msg.header.frame_id = "odom" # CHANGE HERE: odom/map

# Add point obstacle
# Add line obstacle
obstacle_msg.obstacles.append(ObstacleMsg())
obstacle_msg.obstacles[0].id = 0
obstacle_msg.obstacles[0].polygon.points = [Point32()]
obstacle_msg.obstacles[0].polygon.points[0].x = 1.5
obstacle_msg.obstacles[0].polygon.points[0].y = 0
obstacle_msg.obstacles[0].polygon.points[0].z = 0

line_start = Point32()
line_start.x = -4.5
line_start.y = 1
#line_start.y = -3
line_end = Point32()
line_end.x = -1.5
line_end.y = 1
#line_end.y = -4
obstacle_msg.obstacles[0].polygon.points = [line_start, line_end]

# Add line obstacle
# Add line obstacle
obstacle_msg.obstacles.append(ObstacleMsg())
obstacle_msg.obstacles[1].id = 1
line_start = Point32()
line_start.x = -2.5
line_start.y = 0.5
line_start.x = -4.5
line_start.y = -1
line_start.y = -1
#line_start.y = -3
line_end = Point32()
line_end.x = -2.5
line_end.y = 2
line_end.x = 4.5
line_end.y = -1
#line_end.y = -4
obstacle_msg.obstacles[1].polygon.points = [line_start, line_end]

# Add polygon obstacle

# Add line obstacle
# obstacle_msg.obstacles.append(ObstacleMsg())
# obstacle_msg.obstacles[2].id = 2
# line_start = Point32()
# line_start.x = 1.5
# line_start.y = -1
#line_start.y = -3
# line_end = Point32()
# line_end.x = 4.5
# line_end.y = -1
#line_end.y = -4
# obstacle_msg.obstacles[2].polygon.points = [line_start, line_end]

# Add line obstacle
obstacle_msg.obstacles.append(ObstacleMsg())
obstacle_msg.obstacles[1].id = 2
v1 = Point32()
v1.x = -1
v1.y = -1
v2 = Point32()
v2.x = -0.5
v2.y = -1.5
v3 = Point32()
v3.x = 0
v3.y = -1
obstacle_msg.obstacles[2].polygon.points = [v1, v2, v3]
obstacle_msg.obstacles[2].id = 2
line_start = Point32()
line_start.x = 1.5
line_start.y = 1
#line_start.y = -3
line_end = Point32()
line_end.x = 4.5
line_end.y = 1
#line_end.y = -4
obstacle_msg.obstacles[2].polygon.points = [line_start, line_end]

# Add line obstacle
obstacle_msg.obstacles.append(ObstacleMsg())
obstacle_msg.obstacles[3].id = 3
line_start = Point32()
line_start.x = 0
line_start.y = -1
#line_start.y = -3
line_end = Point32()
line_end.x = 0
line_end.y = 0.5
#line_end.y = -4
obstacle_msg.obstacles[3].polygon.points = [line_start, line_end]






r = rospy.Rate(10) # 10hz
Expand Down