Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/ros2' into feature/support-jazzy
Browse files Browse the repository at this point in the history
  • Loading branch information
chama1176 committed Nov 7, 2024
2 parents e96d86a + 15800b2 commit 14f8e01
Show file tree
Hide file tree
Showing 14 changed files with 937 additions and 16 deletions.
2 changes: 1 addition & 1 deletion sciurus17/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>sciurus17</name>
<version>3.0.0</version>
<version>3.1.0</version>
<description>ROS 2 package suite of Sciurus17</description>
<maintainer email="[email protected]">RT Corporation</maintainer>

Expand Down
2 changes: 1 addition & 1 deletion sciurus17_control/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>sciurus17_control</name>
<version>3.0.0</version>
<version>3.1.0</version>
<description>The Sciurus17 control package</description>
<maintainer email="[email protected]">RT Corporation</maintainer>
<license>Apache License 2.0</license>
Expand Down
6 changes: 6 additions & 0 deletions sciurus17_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ find_package(control_msgs REQUIRED)
find_package(image_geometry REQUIRED)
find_package(moveit_ros_planning_interface REQUIRED)
find_package(OpenCV REQUIRED COMPONENTS core)
find_package(pcl_conversions REQUIRED)
find_package(pcl_ros REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(rclcpp_action REQUIRED)
Expand Down Expand Up @@ -115,6 +117,8 @@ set(executable_list
waist_control
pick_and_place_right_arm_waist
pick_and_place_left_arm
pick_and_place_tf
point_cloud_detection
)
foreach(loop_var IN LISTS executable_list)
add_executable(${loop_var} src/${loop_var}.cpp)
Expand All @@ -126,6 +130,8 @@ foreach(loop_var IN LISTS executable_list)
image_geometry
moveit_ros_planning_interface
OpenCV
pcl_ros
pcl_conversions
rclcpp
tf2_geometry_msgs
control_msgs
Expand Down
20 changes: 20 additions & 0 deletions sciurus17_examples/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
- [pick\_and\_place\_left\_arm](#pick_and_place_left_arm)
- [head\_camera\_tracking](#head_camera_tracking)
- [chest\_camera\_tracking](#chest_camera_tracking)
- [point\_cloud\_detection](#point_cloud_detection)

## 準備(実機を使う場合)

Expand Down Expand Up @@ -93,6 +94,7 @@ ros2 launch sciurus17_examples example.launch.py example:='gripper_control' use_
- [pick\_and\_place\_left\_arm](#pick_and_place_left_arm)
- [head\_camera\_tracking](#head_camera_tracking)
- [chest\_camera\_tracking](#chest_camera_tracking)
- [point\_cloud\_detection](#point_cloud_detection)

実行できるサンプルの一覧は、`example.launch.py`にオプション`-s`を付けて実行することで表示できます。

Expand Down Expand Up @@ -203,3 +205,21 @@ ros2 launch sciurus17_examples chest_camera_tracking.launch.py
[back to example list](#examples)

---

### point_cloud_detection

点群から物体を検出して掴むコード例です。

検出された物体位置はtfのフレームとして配信されます。
tfの`frame_id`は検出された順に`target_0``target_1``target_2`…に設定されます。
掴む対象はSciurus17前方の0.3 mの範囲にある`target_0`に設定されています。
物体検出には[Point Cloud Library](https://pointclouds.org/)を使用しています。

次のコマンドを実行します
```sh
ros2 launch sciurus17_examples camera_example.launch.py example:='point_cloud_detection'
```

[back to example list](#examples)

---
89 changes: 89 additions & 0 deletions sciurus17_examples/launch/camera_example.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
# Copyright 2024 RT Corporation
#
# 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 sciurus17_description.robot_description_loader import RobotDescriptionLoader
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import SetParameter
from launch_ros.actions import Node
import yaml


def load_file(package_name, file_path):
package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path)

try:
with open(absolute_file_path, 'r') as file:
return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None


def load_yaml(package_name, file_path):
package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path)

try:
with open(absolute_file_path, 'r') as file:
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None


def generate_launch_description():
description_loader = RobotDescriptionLoader()

robot_description_semantic_config = load_file(
'sciurus17_moveit_config', 'config/sciurus17.srdf')
robot_description_semantic = {
'robot_description_semantic': robot_description_semantic_config}

kinematics_yaml = load_yaml('sciurus17_moveit_config', 'config/kinematics.yaml')

declare_example_name = DeclareLaunchArgument(
'example', default_value='point_cloud_detection',
description=('Set an example executable name: '
'[point_cloud_detection]')
)

declare_use_sim_time = DeclareLaunchArgument(
'use_sim_time', default_value='false',
description=('Set true when using the gazebo simulator.')
)

picking_node = Node(name="pick_and_place_tf",
package='sciurus17_examples',
executable='pick_and_place_tf',
output='screen',
parameters=[{'robot_description': description_loader.load()},
robot_description_semantic,
kinematics_yaml])

detection_node = Node(name=[LaunchConfiguration('example'), '_node'],
package='sciurus17_examples',
executable=LaunchConfiguration('example'),
output='screen')

return LaunchDescription([
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
picking_node,
declare_example_name,
detection_node
])
3 changes: 2 additions & 1 deletion sciurus17_examples/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>sciurus17_examples</name>
<version>3.0.0</version>
<version>3.1.0</version>
<description>examples of Sciurus17 ROS package</description>

<maintainer email="[email protected]">RT Corporation</maintainer>
Expand All @@ -24,6 +24,7 @@
<depend>image_geometry</depend>
<depend>libopencv-dev</depend>
<depend>moveit_ros_planning_interface</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2_geometry_msgs</depend>
Expand Down
Loading

0 comments on commit 14f8e01

Please sign in to comment.