Skip to content

Commit afd7c0d

Browse files
committed
Added ros_control plugin to RRBot
1 parent 26249e5 commit afd7c0d

18 files changed

+189
-599
lines changed

rrbot_control/CMakeLists.txt

+128
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,128 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(rrbot_control)
3+
4+
## Find catkin macros and libraries
5+
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
6+
## is used, also find other catkin packages
7+
find_package(catkin REQUIRED)
8+
9+
## System dependencies are found with CMake's conventions
10+
# find_package(Boost REQUIRED COMPONENTS system)
11+
12+
13+
## Uncomment this if the package has a setup.py. This macro ensures
14+
## modules and global scripts declared therein get installed
15+
## See http://ros.org/doc/groovy/api/catkin/html/user_guide/setup_dot_py.html
16+
# catkin_python_setup()
17+
18+
#######################################
19+
## Declare ROS messages and services ##
20+
#######################################
21+
22+
## Generate messages in the 'msg' folder
23+
# add_message_files(
24+
# FILES
25+
# Message1.msg
26+
# Message2.msg
27+
# )
28+
29+
## Generate services in the 'srv' folder
30+
# add_service_files(
31+
# FILES
32+
# Service1.srv
33+
# Service2.srv
34+
# )
35+
36+
## Generate added messages and services with any dependencies listed here
37+
# generate_messages(
38+
# DEPENDENCIES
39+
# std_msgs # Or other packages containing msgs
40+
# )
41+
42+
###################################
43+
## catkin specific configuration ##
44+
###################################
45+
## The catkin_package macro generates cmake config files for your package
46+
## Declare things to be passed to dependent projects
47+
## LIBRARIES: libraries you create in this project that dependent projects also need
48+
## CATKIN_DEPENDS: catkin_packages dependent projects also need
49+
## DEPENDS: system dependencies of this project that dependent projects also need
50+
catkin_package(
51+
# INCLUDE_DIRS include
52+
# LIBRARIES rrbot_control
53+
# CATKIN_DEPENDS other_catkin_pkg
54+
# DEPENDS system_lib
55+
)
56+
57+
###########
58+
## Build ##
59+
###########
60+
61+
## Specify additional locations of header files
62+
## Your package locations should be listed before other locations
63+
# include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
64+
65+
## Declare a cpp library
66+
# add_library(rrbot_control
67+
# src/${PROJECT_NAME}/rrbot_control.cpp
68+
# )
69+
70+
## Declare a cpp executable
71+
# add_executable(rrbot_control_node src/rrbot_control_node.cpp)
72+
73+
## Add cmake target dependencies of the executable/library
74+
## as an example, message headers may need to be generated before nodes
75+
# add_dependencies(rrbot_control_node rrbot_control_generate_messages_cpp)
76+
77+
## Specify libraries to link a library or executable target against
78+
# target_link_libraries(rrbot_control_node
79+
# ${catkin_LIBRARIES}
80+
# )
81+
82+
#############
83+
## Install ##
84+
#############
85+
86+
# all install targets should use catkin DESTINATION variables
87+
# See http://ros.org/doc/groovy/api/catkin/html/adv_user_guide/variables.html
88+
89+
## Mark executable scripts (Python etc.) for installation
90+
## in contrast to setup.py, you can choose the destination
91+
# install(PROGRAMS
92+
# scripts/my_python_script
93+
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
94+
# )
95+
96+
## Mark executables and/or libraries for installation
97+
# install(TARGETS rrbot_control rrbot_control_node
98+
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
99+
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
100+
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
101+
# )
102+
103+
## Mark cpp header files for installation
104+
# install(DIRECTORY include/${PROJECT_NAME}/
105+
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
106+
# FILES_MATCHING PATTERN "*.h"
107+
# PATTERN ".svn" EXCLUDE
108+
# )
109+
110+
## Mark other files for installation (e.g. launch and bag files, etc.)
111+
# install(FILES
112+
# # myfile1
113+
# # myfile2
114+
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
115+
# )
116+
117+
#############
118+
## Testing ##
119+
#############
120+
121+
## Add gtest based cpp test target and link libraries
122+
# catkin_add_gtest(${PROJECT_NAME}-test test/test_rrbot_control.cpp)
123+
# if(TARGET ${PROJECT_NAME}-test)
124+
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
125+
# endif()
126+
127+
## Add folders to be run by python nosetests
128+
# catkin_add_nosetests(test)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
rrbot:
2+
joint1_position_controller:
3+
type: effort_controllers/JointPositionController
4+
joint: joint1
5+
pid: {p: 100.0, i: 0.01, d: 10.0}
6+
joint2_position_controller:
7+
type: effort_controllers/JointPositionController
8+
joint: joint2
9+
pid: {p: 100.0, i: 0.01, d: 10.0}
+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
<launch>
2+
3+
<!-- load the controllers -->
4+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
5+
output="screen" ns="/rrbot" args="--namespace=/rrbot
6+
joint1_position_controller
7+
joint2_position_controller"/>
8+
9+
<!-- Load joint controller configurations from YAML file to parameter server -->
10+
<rosparam file="$(find rrbot_control)/config/rrbot_ros_control.yaml" command="load"/>
11+
12+
</launch>

rrbot_control/package.xml

+24
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
<?xml version="1.0"?>
2+
<package>
3+
<name>rrbot_control</name>
4+
<version>0.0.0</version>
5+
<description>The rrbot_control package</description>
6+
7+
<maintainer email="[email protected]">Dave Coleman</maintainer>
8+
9+
<license>BSD</license>
10+
11+
<url type="website">http://http://gazebosim.org/w/index.php?title=Tutorials/1.9/Using_A_URDF_In_Gazebo</url>
12+
<url type="bugtracker">https://github.com/osrf/gazebo_ros_demos/issues</url>
13+
<url type="repository">https://github.com/osrf/gazebo_ros_demos</url>
14+
15+
<author email="[email protected]">Dave Coleman</author>
16+
17+
<buildtool_depend>catkin</buildtool_depend>
18+
19+
<run_depend>controller_manager</run_depend>
20+
21+
<export>
22+
</export>
23+
24+
</package>

rrbot_description/urdf/rrbot.gazebo

+1-12
Original file line numberDiff line numberDiff line change
@@ -4,21 +4,10 @@
44
<!-- ros_control plugin -->
55
<gazebo>
66
<plugin name="ros_control" filename="libgazebo_ros_control.so">
7-
<robotNamespace>rrbot/ros_control</robotNamespace>
8-
<controlPeriod>0.001</controlPeriod>
9-
<joint>joint1</joint>
10-
<joint>joint2</joint>
7+
<robotNamespace>/rrbot</robotNamespace>
118
</plugin>
129
</gazebo>
1310

14-
<!--gazebo>
15-
<plugin name="ros_control" filename="libros_control_gazebo_plugin.so">
16-
<ns>rrbot/ros_control</ns>
17-
<robotSimType>rrbot_gazebo/RobotSimRRBot</robotSimType>
18-
<controlPeriod>0.001</controlPeriod>
19-
</plugin>
20-
</gazebo-->
21-
2211
<!-- Link1 -->
2312
<gazebo reference="link1">
2413
<material>Gazebo/Orange</material>

rrbot_description/urdf/rrbot.xacro

+5-5
Original file line numberDiff line numberDiff line change
@@ -182,16 +182,16 @@
182182
</inertial>
183183
</link>
184184

185-
<!--transmission name="joint1_trans" type="pr2_mechanism_model/SimpleTransmission">
186-
<actuator name="joint1_motor"/>
185+
<transmission name="tran1" type="transmission_interface/SimpleTransmission">
187186
<joint name="joint1"/>
187+
<actuator name="motor1" type="EffortJointInterface" />
188188
<mechanicalReduction>1</mechanicalReduction>
189189
</transmission>
190190

191-
<transmission name="joint2_trans" type="pr2_mechanism_model/SimpleTransmission">
192-
<actuator name="joint2_motor"/>
191+
<transmission name="tran2" type="transmission_interface/SimpleTransmission">
193192
<joint name="joint2"/>
193+
<actuator name="motor2" type="EffortJointInterface" />
194194
<mechanicalReduction>1</mechanicalReduction>
195-
</transmission-->
195+
</transmission>
196196

197197
</robot>

0 commit comments

Comments
 (0)