Skip to content

Commit

Permalink
Merge pull request #42 from igonzf/deploy
Browse files Browse the repository at this point in the history
Updated for inspection
  • Loading branch information
igonzf authored Jul 15, 2024
2 parents 5f4df01 + c9931cf commit f9f74a7
Show file tree
Hide file tree
Showing 12 changed files with 105 additions and 15 deletions.
3 changes: 2 additions & 1 deletion bt_nodes/motion/include/motion/navigation/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ std::string nav_to_pose_truncated_xml =
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
</Sequence>
<Spin spin_dist="1.57"/>
<Wait wait_duration="5"/>
<Spin spin_dist="-1.57"/>
<Wait wait_duration="3"/>
<BackUp backup_dist="0.30" backup_speed="0.05"/>
</RoundRobin>
</ReactiveFallback>
Expand Down
3 changes: 3 additions & 0 deletions robocup_bringup/bt_xml/robot_inspection.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,12 @@
<Sequence>
<Action ID="SetWp"/>
<Action ID="Speak" param="" say_text="Hi, this is Gentlebots, im ready to be inspected"/>
<Action ID="Speak" param="" say_text="Can you please open the door?"/>
<RetryUntilSuccessful num_attempts="-1">
<Condition ID="IsDoorOpen" door_thfloatreshold="1.5"/>
</RetryUntilSuccessful>
<Action ID="MoveAlongAxis" speed="0.25" distance="1.8" axis="x"/>

<Action ID="MoveTo" is_truncated="false" distance_tolerance="0" tf_frame="inspection_zone"/>
<Action ID="Speak" param="" say_text="Please say ready when you finish the inspection"/>
<RetryUntilSuccessful num_attempts="-1">
Expand Down
19 changes: 19 additions & 0 deletions robocup_bringup/bt_xml/setwp_moveto_test.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<root main_tree_to_execute="BehaviorTree">
<!-- ////////// -->
<BehaviorTree ID="BehaviorTree">
<Sequence>
<Action ID="SetWp"/>
<Action ID="MoveTo" distance_tolerance="0" tf_frame="party"/>
</Sequence>
</BehaviorTree>
<!-- ////////// -->
<TreeNodesModel>
<Action ID="MoveTo">
<input_port default="0" name="distance_tolerance"/>
<input_port default="entrance" name="tf_frame"/>
</Action>
<Action ID="SetWp"/>
</TreeNodesModel>
<!-- ////////// -->
</root>
Binary file added robocup_bringup/config/gpsr/robocup_objects.pt
Binary file not shown.
6 changes: 4 additions & 2 deletions robocup_bringup/config/inspection/inspection_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,9 @@
waypoints_names: ["inspection_zone", "exit"]
# allow_duplicate_names: false
waypoints:
inspection_zone: [-1.382, -5.781, -0.253]
exit: [2.441, -2.499, 1.206]
inspection_zone: [14.001, -8.264, -0.044] # REAL ONE
# inspection_zone: [11.499, -7.174, -1.299]
exit: [11.541, -4.412, 1.775]

behaviors_main:
ros__parameters:
Expand All @@ -23,3 +24,4 @@ behaviors_main:
- listen_bt_node
- clean_string_bt_node
- is_door_open_bt_node
- move_along_axis_bt_node
30 changes: 25 additions & 5 deletions robocup_bringup/config/inspection/tiago_nav_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -219,11 +219,11 @@ local_costmap:
height: 3
resolution: 0.05
robot_radius: 0.29
plugins: ["obstacle_layer", "inflation_layer"]
plugins: ["voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.40
inflation_radius: 0.35
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
Expand Down Expand Up @@ -278,7 +278,7 @@ global_costmap:
robot_radius: 0.29
resolution: 0.05
track_unknown_space: true
plugins: ["static_layer", "inflation_layer"]
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
Expand All @@ -299,7 +299,7 @@ global_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.40
inflation_radius: 0.35
clear_people_layer:
plugin: "nav2_costmap_2d::ClearPeopleLayer"
person_radious: 1.0
Expand Down Expand Up @@ -330,7 +330,27 @@ planner_server:
plugin: "nav2_navfn_planner/NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
# allow_unknown: false
# plugin: "nav2_smac_planner/SmacPlanner2D" # In Iron and older versions, "/" was used instead of "::"
# tolerance: 0.125 # tolerance for planning if unable to reach exact pose, in meters
# downsample_costmap: false # whether or not to downsample the map
# downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm)
# allow_unknown: true # allow traveling in unknown space
# max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable
# max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance
# max_planning_time: 2.0 # max time in s for planner to plan, smooth
# cost_travel_multiplier: 10.0 # Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*.
# use_final_approach_orientation: false # Whether to set the final path pose at the goal's orientation to the requested orientation (false) or in line with the approach angle so the robot doesn't rotate to heading (true)
# smoother:
# max_iterations: 1000
# w_smooth: 0.3
# w_data: 0.2
# tolerance: 1.0e-10
# plugin: "nav2_theta_star_planner/ThetaStarPlanner" # In Iron and older versions, "/" was used instead of "::"
# how_many_corners: 8
# w_euc_cost: 1.0
# w_traversal_cost: 2.5
# w_heuristic_cost: 1.0

smoother_server:
ros__parameters:
Expand Down
2 changes: 1 addition & 1 deletion robocup_bringup/launch/gpsr_dependencies.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ def generate_launch_description():
'map': os.path.join(
package_dir,
'maps',
'ir_lab.yaml'),
'robocup_arena_1.yaml'),
}.items()
)

Expand Down
6 changes: 3 additions & 3 deletions robocup_bringup/launch/inspection_dependencies.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,9 @@ def generate_launch_description():

ld = LaunchDescription()
ld.add_action(navigation)
# # ld.add_action(whisper_cmd)
# ld.add_action(audio_common_player_node)
# ld.add_action(audio_common_tts_node)
ld.add_action(whisper_cmd)
ld.add_action(audio_common_player_node)
ld.add_action(audio_common_tts_node)
ld.add_action(real_time)

return ld
44 changes: 44 additions & 0 deletions robocup_bringup/launch/move_to.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# Copyright 2024 Intelligent Robotics Lab - Gentlebots
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():

package_dir = get_package_share_directory('robocup_bringup')

config = os.path.join(
package_dir,
'config',
'tests',
'test_params.yaml'
)

moveto_test = Node(
package='robocup_bringup',
executable='behaviors_main',
parameters=[config],
output='screen',
)

ld = LaunchDescription()

ld.add_action(moveto_test)

return ld
3 changes: 2 additions & 1 deletion robocup_bringup/launch/storing_dependencies.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,13 +100,14 @@ def generate_launch_description():
stopping_words=["\n\n\n\n"],
)

yolo_model = package_dir + "/config/storing_groceries/yolo_groceries.pt"
yolo3d = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(yolo3d_dir, 'launch', 'yolov8_3d.launch.py')
),
launch_arguments={
# 'namespace': 'perception_system',
'model': 'yolov8m-seg.pt', # change to pretrained
'model': yolo_model, # change to pretrained
'input_image_topic': '/head_front_camera/rgb/image_raw',
'input_depth_topic': '/head_front_camera/depth/image_raw',
'input_depth_info_topic': '/head_front_camera/depth/camera_info',
Expand Down
4 changes: 2 additions & 2 deletions robocup_bringup/maps/robocup_arena_1.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
image: robocup_arena_1.pgm
image: robocup_arena_1_modified.pgm
mode: trinary
resolution: 0.05
origin: [1.19, -13.4, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
free_thresh: 0.25
Binary file not shown.

0 comments on commit f9f74a7

Please sign in to comment.