Skip to content

Commit 0a369b5

Browse files
committed
Fix CMake and add building docs
1 parent 77a80df commit 0a369b5

File tree

2 files changed

+16
-2
lines changed

2 files changed

+16
-2
lines changed

CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@ find_package(catkin REQUIRED COMPONENTS
66
roscpp
77
gazebo_ros
88
std_msgs
9-
message_runtime
109
message_generation
1110
)
1211

README.md

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,32 @@
11
Attach two Gazebo models with a virtual joint in a generalized grasp hack
22

3+
# Build
4+
5+
````
6+
mkdir -p gazebo_link_attacher_ws/src
7+
cd gazebo_link_attacher_ws/src
8+
catkin_init_workspace
9+
git clone https://github.com/pal-robotics/gazebo_ros_link_attacher.git
10+
cd ..
11+
catkin_make
12+
source devel/setup.bash
13+
````
14+
15+
316
# Launch
417

518
roslaunch gazebo_ros_link_attacher test_attacher.launch
619

7-
Empty world with the plugin `libgazebo_ros_link_attacher.so` loaded.
20+
Empty world with the plugin `libgazebo_ros_link_attacher.so` loaded (in the *worlds* folder).
821

922
Which provides the `/link_attacher_node/attach_models` topic to specify two models and their links to be attached.
1023

1124
![gazebo screenshot](ss.png)
1225

1326
# Run demo
1427

28+
In another shell, be sure to do `source devel/setup.bash` of your workspace.
29+
1530
rosrun gazebo_ros_link_attacher demo.py
1631

1732
This demo will spawn two boxes and link them.

0 commit comments

Comments
 (0)