-
Notifications
You must be signed in to change notification settings - Fork 195
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge branch 'main' into ch3/trajectory-cache-refactor
- Loading branch information
Showing
43 changed files
with
1,874 additions
and
647 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1 @@ | ||
SINIC |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,6 +1,5 @@ | ||
__pycache__ | ||
**/.git | ||
**/.github | ||
**/_scripts | ||
**/_static | ||
**/_templates | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
1 change: 1 addition & 0 deletions
1
doc/examples/motion_planning_python_api/launch/motion_planning_python_api_tutorial.launch.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,13 +1,2 @@ | ||
add_executable(cylinder_segment src/cylinder_segment.cpp) | ||
target_link_libraries(cylinder_segment ${catkin_LIBRARIES}) | ||
|
||
add_executable(bag_publisher_maintain_time src/bag_publisher_maintain_time.cpp) | ||
target_link_libraries(bag_publisher_maintain_time ${catkin_LIBRARIES} ${Boost_LIBRARIES}) | ||
|
||
install( | ||
TARGETS | ||
bag_publisher_maintain_time | ||
cylinder_segment | ||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) | ||
|
||
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) | ||
install(DIRECTORY urdf launch meshes config worlds rviz2 | ||
DESTINATION share/moveit2_tutorials) |
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,22 @@ | ||
sensors: | ||
- camera_1_pointcloud | ||
- camera_2_depth_image | ||
camera_1_pointcloud: | ||
sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater | ||
point_cloud_topic: /camera_1/points | ||
max_range: 5.0 | ||
point_subsample: 1 | ||
padding_offset: 0.1 | ||
padding_scale: 1.0 | ||
max_update_rate: 1.0 | ||
filtered_cloud_topic: /camera_1/filtered_points | ||
camera_2_depth_image: | ||
sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater | ||
image_topic: /camera_2/depth/image_raw | ||
queue_size: 5 | ||
near_clipping_plane_distance: 0.3 | ||
far_clipping_plane_distance: 5.0 | ||
shadow_threshold: 0.2 | ||
padding_scale: 1.0 | ||
max_update_rate: 1.0 | ||
filtered_cloud_topic: /camera_2/filtered_points |
Binary file not shown.
Binary file added
BIN
+197 KB
doc/examples/perception_pipeline/images/perception_pipeline_demo_gazebo_screen.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added
BIN
+162 KB
...les/perception_pipeline/images/perception_pipeline_depth_camera_environment.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
153 changes: 153 additions & 0 deletions
153
doc/examples/perception_pipeline/launch/depth_camera_environment.launch.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,153 @@ | ||
import os | ||
from ament_index_python.packages import get_package_share_directory | ||
from launch import LaunchDescription | ||
from launch.substitutions import Command | ||
from launch_ros.substitutions import FindPackageShare | ||
from launch_ros.actions import Node | ||
from launch.actions import IncludeLaunchDescription | ||
from launch.substitutions import PathJoinSubstitution | ||
import math | ||
|
||
|
||
def generate_launch_description(): | ||
urdf_file = os.path.join( | ||
get_package_share_directory("moveit2_tutorials"), | ||
"urdf/realsense_d435/camera.urdf.xacro", | ||
) | ||
|
||
# The list presents the pose in euler coordinates ordered x, y, z, yaw, pitch, roll respectively. | ||
camera_1_pose = ["-1", "-1", "0", f"{math.pi/2}", "0.0", "0.0"] | ||
camera_2_pose = ["-1", "1", "0", f"-{math.pi/2}", "0.0", "0.0"] | ||
|
||
# It is necessary for gazebo spawner to use the description of camera_1 in gazebo environment | ||
camera_1_robot_state_publisher_node = Node( | ||
package="robot_state_publisher", | ||
executable="robot_state_publisher", | ||
name="robot_state_publisher", | ||
output="screen", | ||
parameters=[ | ||
{ | ||
"use_sim_time": True, | ||
"robot_description": Command( | ||
[f"xacro {urdf_file}", " camera_name:='camera_1'"] | ||
), | ||
} | ||
], | ||
remappings=[ | ||
("robot_description", "/camera_1/robot_description"), | ||
], | ||
) | ||
|
||
# It is necessary for spawning camera_1 in gazebo environment | ||
camera_1_gazebo_spawner_node = Node( | ||
package="gazebo_ros", | ||
executable="spawn_entity.py", | ||
arguments=[ | ||
"-entity", | ||
"mr_camera", | ||
"-topic", | ||
"/camera_1/robot_description", | ||
"-x", | ||
camera_1_pose[0], | ||
"-y", | ||
camera_1_pose[1], | ||
"-z", | ||
camera_1_pose[2], | ||
"-Y", | ||
camera_1_pose[3], | ||
"-P", | ||
camera_1_pose[4], | ||
"-R", | ||
camera_1_pose[5], | ||
], | ||
output="screen", | ||
) | ||
|
||
# It is necessary to make transformation between world frame and camera frames enable later. | ||
camera_1_tf_from_world_publisher_node = Node( | ||
package="tf2_ros", | ||
executable="static_transform_publisher", | ||
name="static_transform_publisher", | ||
output="log", | ||
arguments=[*camera_1_pose, "world", "camera_1_base_link"], | ||
) | ||
|
||
# It is necessary for gazebo spawner to use the description of camera_2 in gazebo environment | ||
camera_2_gazebo_spawner_node = Node( | ||
package="robot_state_publisher", | ||
executable="robot_state_publisher", | ||
name="robot_state_publisher2", | ||
output="screen", | ||
parameters=[ | ||
{ | ||
"use_sim_time": True, | ||
"robot_description": Command( | ||
[f"xacro {urdf_file}", " camera_name:='camera_2'"] | ||
), | ||
} | ||
], | ||
remappings=[ | ||
("robot_description", "/camera_2/robot_description"), | ||
], | ||
) | ||
|
||
# It is necessary for spawning camera_2 in gazebo environment | ||
camera_2_robot_state_publisher_node = Node( | ||
package="gazebo_ros", | ||
executable="spawn_entity.py", | ||
name="spawn2", | ||
arguments=[ | ||
"-entity", | ||
"mr_camera2", | ||
"-topic", | ||
"/camera_2/robot_description", | ||
"-x", | ||
camera_2_pose[0], | ||
"-y", | ||
camera_2_pose[1], | ||
"-z", | ||
camera_2_pose[2], | ||
"-Y", | ||
camera_2_pose[3], | ||
"-P", | ||
camera_2_pose[4], | ||
"-R", | ||
camera_2_pose[5], | ||
], | ||
output="screen", | ||
) | ||
|
||
# It is necessary to make transformation between world frame and camera frames enable later. | ||
camera_2_tf_from_world_publisher_node = Node( | ||
package="tf2_ros", | ||
executable="static_transform_publisher", | ||
name="static_transform_publisher", | ||
output="log", | ||
arguments=[*camera_2_pose, "world", "camera_2_base_link"], | ||
) | ||
|
||
# It is necessary to open previously created gazebo world for perception pipeline demo. | ||
gazebo_launch = IncludeLaunchDescription( | ||
PathJoinSubstitution( | ||
[FindPackageShare("gazebo_ros"), "launch", "gazebo.launch.py"] | ||
), | ||
launch_arguments={ | ||
"world": os.path.join( | ||
get_package_share_directory("moveit2_tutorials"), | ||
"worlds", | ||
"perception_pipeline_demo.world", | ||
), | ||
}.items(), | ||
) | ||
|
||
return LaunchDescription( | ||
[ | ||
camera_1_robot_state_publisher_node, | ||
camera_1_gazebo_spawner_node, | ||
camera_1_tf_from_world_publisher_node, | ||
camera_2_robot_state_publisher_node, | ||
camera_2_gazebo_spawner_node, | ||
camera_2_tf_from_world_publisher_node, | ||
gazebo_launch, | ||
] | ||
) |
7 changes: 0 additions & 7 deletions
7
doc/examples/perception_pipeline/launch/detect_and_add_cylinder_collision_object_demo.launch
This file was deleted.
Oops, something went wrong.
11 changes: 0 additions & 11 deletions
11
doc/examples/perception_pipeline/launch/obstacle_avoidance_demo.launch
This file was deleted.
Oops, something went wrong.
Oops, something went wrong.