Skip to content

Commit

Permalink
Merge pull request #3 from Yolnan/devel
Browse files Browse the repository at this point in the history
launchfile and README.md updates
  • Loading branch information
marip8 authored Mar 15, 2024
2 parents 2420141 + 0f2d8d9 commit be344fe
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 58 deletions.
56 changes: 1 addition & 55 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,78 +1,24 @@
# SNP Implementation for Robotic Blending Milesone 5
# SNP Implementation for Robotic Blending Milestone 5

This demo uses a Motoman MH180 with an Intel RealSense camera to reconstruct the surface of an arbitrary part and generate motion plans for grinding the part in a raster pattern

## Build Setup

1. Follow the [build setup instructions](https://github.com/ros-industrial-consortium/scan_n_plan_workshop#build-setup) for the main repository

1. Clone the application-specific ROS2 dependencies into the same workspace
```
cd <snp_workspace>
vcs import src < snp_automate_2022/dependencies.repos
```

## Build

```
colcon build --cmake-args -DTESSERACT_BUILD_FCL=OFF
```
## ROS1 Hardware Interface Software Installation
Install the requisite ROS1 driver software to run the application on hardware
**Note: this step is not required to run the application in simulation only**
1. Build the ros1_bridge
- Create a new workspace, clone this branch of the `ros1_bridge` repository
```bash
git clone -b action_bridge https://github.com/ipa-hsd/ros1_bridge.git
```
- Source the both ROS distros
```bash
source /opt/ros/foxy/setup.bash
source /opt/ros/noetic/setup.bash
```
- Build the bridge
```bash
colcon build --symlink-install --packages-select ros1_bridge --cmake-force-configure
```
1. Build the ROS1 workspace
- Create a new workspace, clone this commit of the `motoman` repository
```bash
git clone -b 63c94ec https://github.com/ros-industrial/motoman.git
```
- Source the ROS1 installation
```bash
source /opt/ros/noetic/setup.bash
```
- Build the repo
```bash
catkin build
```
## Running the system
### Simulation
```bash
ros2 launch snp_blending start.launch.xml
```

### On Hardware
1. Start the ROS1 launch file in a new terminal
```bash
cd <ros1_workspace>
source devel/setup.bash
roslaunch motoman_hc10_support robot_interface_streaming_hc10.launch robot_ip:=192.168.1.31 controller:=yrc1000
```
1. Run the bridge in a second terminal
```bash
cd <bridge_workspace>
source install/setup.bash
ros2 run ros1_bridge dynamic_bridge --bridge-all-1to2-topics
```
1. Start the ROS2 launch file in a third terminal
```bash
cd <snp_workspace>
source install/setup.bash
Expand Down
9 changes: 6 additions & 3 deletions launch/start.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@
<arg name="mesh_file" default="$(find-pkg-share snp_blending)/meshes/part_scan.ply"/>
<arg name="scan_trajectory_file" default="$(find-pkg-share snp_blending)/config/scan_traj.yaml"/>
<arg name="verbose" default="True"/>
<arg name="touch_links" default="[table, base_link, floor]"/>
<arg name="scan_disabled_contact_links" default="[table, base_link, floor]"/>
<arg name="scan_reduced_contact_links" default="[buffy_tcp]"/>
<arg name="robot_description_file" default="$(find-pkg-share snp_blending)/urdf/workcell.xacro"/>
<arg name="robot_description" default="$(command 'xacro $(var robot_description_file) ros_distro:=$(env ROS_DISTRO)')"/>
<arg name="robot_description_semantic" default="$(command 'cat $(find-pkg-share snp_blending)/config/workcell.srdf')"/>
Expand Down Expand Up @@ -41,6 +42,7 @@
<param name="camera_frame" value="camera_color_optical_frame"/>
<param name="robot_description" value="$(var robot_description)"/>
<param name="robot_description_semantic" value="$(var robot_description_semantic)"/>
<param name="follow_joint_trajectory_action" value="$(var follow_joint_trajectory_action)"/>
<!-- TSDF parameters -->
<param name="tsdf.min.x" value="0.0"/>
<param name="tsdf.min.y" value="0.0"/>
Expand All @@ -66,7 +68,7 @@
<include file="$(find-pkg-share realsense2_camera)/launch/rs_launch.py">
<arg name="align_depth.enable" value="true"/>
<arg name="pointcloud.enable" value="true"/>
<arg name="rgb_camera.profile" value="640x360x90"/>
<arg name="rgb_camera.profile" value="640x360x30"/>
</include>
</group>
<!-- Launch Open3d Interface Node (Sim) -->
Expand All @@ -83,7 +85,8 @@
<arg name="robot_description" value="$(var robot_description)"/>
<arg name="robot_description_semantic" value="$(var robot_description_semantic)"/>
<arg name="verbose" value="$(var verbose)"/>
<arg name="touch_links" value="$(var touch_links)"/>
<arg name="scan_disabled_contact_links" value="$(var scan_disabled_contact_links)"/>
<arg name="scan_reduced_contact_links" value="$(var scan_reduced_contact_links)"/>
</include>

<node pkg="snp_scanning" exec="scan_motion_plan_from_file_node">
Expand Down

0 comments on commit be344fe

Please sign in to comment.