00001
00002 import roslib; roslib.load_manifest('cob_gazebo')
00003
00004 import rospy
00005 import tf
00006 import actionlib
00007
00008 from pr2_controllers_msgs.msg import JointTrajectoryAction
00009 from move_base_msgs.msg import MoveBaseAction
00010
00011
00012 from cob_srvs.srv import *
00013
00014 class gazebo_services():
00015
00016 def __init__(self):
00017
00018 self.base_client = actionlib.SimpleActionClient('/move_base', MoveBaseAction)
00019
00020
00021
00022
00023
00024
00025 self.torso_client = actionlib.SimpleActionClient('/torso_controller/joint_trajectory_action', JointTrajectoryAction)
00026 self.torso_init_srv = rospy.Service('/torso_controller/init', Trigger, self.torso_init_cb)
00027 self.torso_stop_srv = rospy.Service('/torso_controller/stop', Trigger, self.torso_stop_cb)
00028 self.torso_recover_srv = rospy.Service('/torso_controller/recover', Trigger, self.torso_recover_cb)
00029 self.torso_set_operation_mode_srv = rospy.Service('/torso_controller/set_operation_mode', SetOperationMode, self.torso_set_operation_mode_cb)
00030
00031
00032 self.tray_client = actionlib.SimpleActionClient('/tray_controller/joint_trajectory_action', JointTrajectoryAction)
00033 self.tray_init_srv = rospy.Service('/tray_controller/init', Trigger, self.tray_init_cb)
00034 self.tray_stop_srv = rospy.Service('/tray_controller/stop', Trigger, self.tray_stop_cb)
00035 self.tray_recover_srv = rospy.Service('/tray_controller/recover', Trigger, self.tray_recover_cb)
00036 self.tray_set_operation_mode_srv = rospy.Service('/tray_controller/set_operation_mode', SetOperationMode, self.tray_set_operation_mode_cb)
00037
00038
00039 self.arm_client = actionlib.SimpleActionClient('/arm_controller/joint_trajectory_action', JointTrajectoryAction)
00040 self.arm_init_srv = rospy.Service('/arm_controller/init', Trigger, self.arm_init_cb)
00041 self.arm_stop_srv = rospy.Service('/arm_controller/stop', Trigger, self.arm_stop_cb)
00042 self.arm_recover_srv = rospy.Service('/arm_controller/recover', Trigger, self.arm_recover_cb)
00043 self.arm_set_operation_mode_srv = rospy.Service('/arm_controller/set_operation_mode', SetOperationMode, self.arm_set_operation_mode_cb)
00044
00045
00046 self.arm_left_client = actionlib.SimpleActionClient('/arm_left_controller/joint_trajectory_action', JointTrajectoryAction)
00047 self.arm_left_init_srv = rospy.Service('/arm_left_controller/init', Trigger, self.arm_left_init_cb)
00048 self.arm_left_stop_srv = rospy.Service('/arm_left_controller/stop', Trigger, self.arm_left_stop_cb)
00049 self.arm_left_recover_srv = rospy.Service('/arm_left_controller/recover', Trigger, self.arm_left_recover_cb)
00050 self.arm_left_set_operation_mode_srv = rospy.Service('/arm_left_controller/set_operation_mode', SetOperationMode, self.arm_left_set_operation_mode_cb)
00051
00052
00053 self.arm_right_client = actionlib.SimpleActionClient('/arm_right_controller/joint_trajectory_action', JointTrajectoryAction)
00054 self.arm_right_init_srv = rospy.Service('/arm_right_controller/init', Trigger, self.arm_right_init_cb)
00055 self.arm_right_stop_srv = rospy.Service('/arm_right_controller/stop', Trigger, self.arm_right_stop_cb)
00056 self.arm_right_recover_srv = rospy.Service('/arm_right_controller/recover', Trigger, self.arm_right_recover_cb)
00057 self.arm_right_set_operation_mode_srv = rospy.Service('/arm_right_controller/set_operation_mode', SetOperationMode, self.arm_right_set_operation_mode_cb)
00058
00059
00060 self.sdh_client = actionlib.SimpleActionClient('/sdh_controller/joint_trajectory_action', JointTrajectoryAction)
00061 self.sdh_init_srv = rospy.Service('/sdh_controller/init', Trigger, self.sdh_init_cb)
00062 self.sdh_stop_srv = rospy.Service('/sdh_controller/stop', Trigger, self.sdh_stop_cb)
00063 self.sdh_recover_srv = rospy.Service('/sdh_controller/recover', Trigger, self.sdh_recover_cb)
00064 self.sdh_set_operation_mode_srv = rospy.Service('/sdh_controller/set_operation_mode', SetOperationMode, self.sdh_set_operation_mode_cb)
00065
00066
00067 self.sdh_left_client = actionlib.SimpleActionClient('/sdh_left_controller/joint_trajectory_action', JointTrajectoryAction)
00068 self.sdh_left_init_srv = rospy.Service('/sdh_left_controller/init', Trigger, self.sdh_left_init_cb)
00069 self.sdh_left_stop_srv = rospy.Service('/sdh_left_controller/stop', Trigger, self.sdh_left_stop_cb)
00070 self.sdh_left_recover_srv = rospy.Service('/sdh_left_controller/recover', Trigger, self.sdh_left_recover_cb)
00071 self.sdh_left_set_operation_mode_srv = rospy.Service('/sdh_left_controller/set_operation_mode', SetOperationMode, self.sdh_left_set_operation_mode_cb)
00072
00073
00074 self.sdh_right_client = actionlib.SimpleActionClient('/sdh_right_controller/joint_trajectory_action', JointTrajectoryAction)
00075 self.sdh_right_init_srv = rospy.Service('/sdh_right_controller/init', Trigger, self.sdh_right_init_cb)
00076 self.sdh_right_stop_srv = rospy.Service('/sdh_right_controller/stop', Trigger, self.sdh_right_stop_cb)
00077 self.sdh_right_recover_srv = rospy.Service('/sdh_right_controller/recover', Trigger, self.sdh_right_recover_cb)
00078 self.sdh_right_set_operation_mode_srv = rospy.Service('/sdh_right_controller/set_operation_mode', SetOperationMode, self.sdh_right_set_operation_mode_cb)
00079
00080
00081 self.head_client = actionlib.SimpleActionClient('/head_controller/joint_trajectory_action', JointTrajectoryAction)
00082 self.head_init_srv = rospy.Service('/head_controller/init', Trigger, self.head_init_cb)
00083 self.head_stop_srv = rospy.Service('/head_controller/stop', Trigger, self.head_stop_cb)
00084 self.head_recover_srv = rospy.Service('/head_controller/recover', Trigger, self.head_recover_cb)
00085 self.head_set_operation_mode_srv = rospy.Service('/head_controller/set_operation_mode', SetOperationMode, self.head_set_operation_mode_cb)
00086
00087
00088 def base_init_cb(self, req):
00089 resp = TriggerResponse()
00090 resp.success.data = True
00091 return resp
00092
00093 def base_stop_cb(self, req):
00094 self.base_client.cancel_all_goals()
00095 resp = TriggerResponse()
00096 resp.success.data = True
00097 return resp
00098
00099 def base_recover_cb(self, req):
00100 resp = TriggerResponse()
00101 resp.success.data = True
00102 return resp
00103
00104 def base_set_operation_mode_cb(self, req):
00105 resp = SetOperationModeResponse()
00106 resp.success.data = True
00107 return resp
00108
00109
00110 def torso_init_cb(self, req):
00111 resp = TriggerResponse()
00112 resp.success.data = True
00113 return resp
00114
00115 def torso_stop_cb(self, req):
00116 self.torso_client.cancel_all_goals()
00117 resp = TriggerResponse()
00118 resp.success.data = True
00119 return resp
00120
00121 def torso_recover_cb(self, req):
00122 resp = TriggerResponse()
00123 resp.success.data = True
00124 return resp
00125
00126 def torso_set_operation_mode_cb(self, req):
00127 resp = SetOperationModeResponse()
00128 resp.success.data = True
00129 return resp
00130
00131
00132 def tray_init_cb(self, req):
00133 resp = TriggerResponse()
00134 resp.success.data = True
00135 return resp
00136
00137 def tray_stop_cb(self, req):
00138 self.tray_client.cancel_all_goals()
00139 resp = TriggerResponse()
00140 resp.success.data = True
00141 return resp
00142
00143 def tray_recover_cb(self, req):
00144 resp = TriggerResponse()
00145 resp.success.data = True
00146 return resp
00147
00148 def tray_set_operation_mode_cb(self, req):
00149 resp = SetOperationModeResponse()
00150 resp.success.data = True
00151 return resp
00152
00153
00154 def arm_init_cb(self, req):
00155 resp = TriggerResponse()
00156 resp.success.data = True
00157 return resp
00158
00159 def arm_stop_cb(self, req):
00160 self.arm_client.cancel_all_goals()
00161 resp = TriggerResponse()
00162 resp.success.data = True
00163 return resp
00164
00165 def arm_recover_cb(self, req):
00166 resp = TriggerResponse()
00167 resp.success.data = True
00168 return resp
00169
00170 def arm_set_operation_mode_cb(self, req):
00171 resp = SetOperationModeResponse()
00172 resp.success.data = True
00173 return resp
00174
00175
00176 def arm_left_init_cb(self, req):
00177 resp = TriggerResponse()
00178 resp.success.data = True
00179 return resp
00180
00181 def arm_left_stop_cb(self, req):
00182 self.arm_left_client.cancel_all_goals()
00183 resp = TriggerResponse()
00184 resp.success.data = True
00185 return resp
00186
00187 def arm_left_recover_cb(self, req):
00188 resp = TriggerResponse()
00189 resp.success.data = True
00190 return resp
00191
00192 def arm_left_set_operation_mode_cb(self, req):
00193 resp = SetOperationModeResponse()
00194 resp.success.data = True
00195 return resp
00196
00197
00198 def arm_right_init_cb(self, req):
00199 resp = TriggerResponse()
00200 resp.success.data = True
00201 return resp
00202
00203 def arm_right_stop_cb(self, req):
00204 self.arm_right_client.cancel_all_goals()
00205 resp = TriggerResponse()
00206 resp.success.data = True
00207 return resp
00208
00209 def arm_right_recover_cb(self, req):
00210 resp = TriggerResponse()
00211 resp.success.data = True
00212 return resp
00213
00214 def arm_right_set_operation_mode_cb(self, req):
00215 resp = SetOperationModeResponse()
00216 resp.success.data = True
00217 return resp
00218
00219
00220 def sdh_init_cb(self, req):
00221 resp = TriggerResponse()
00222 resp.success.data = True
00223 return resp
00224
00225 def sdh_stop_cb(self, req):
00226 self.sdh_client.cancel_all_goals()
00227 resp = TriggerResponse()
00228 resp.success.data = True
00229 return resp
00230
00231 def sdh_recover_cb(self, req):
00232 resp = TriggerResponse()
00233 resp.success.data = True
00234 return resp
00235
00236 def sdh_set_operation_mode_cb(self, req):
00237 resp = SetOperationModeResponse()
00238 resp.success.data = True
00239 return resp
00240
00241
00242 def sdh_left_init_cb(self, req):
00243 resp = TriggerResponse()
00244 resp.success.data = True
00245 return resp
00246
00247 def sdh_left_stop_cb(self, req):
00248 self.sdh_left_client.cancel_all_goals()
00249 resp = TriggerResponse()
00250 resp.success.data = True
00251 return resp
00252
00253 def sdh_left_recover_cb(self, req):
00254 resp = TriggerResponse()
00255 resp.success.data = True
00256 return resp
00257
00258 def sdh_left_set_operation_mode_cb(self, req):
00259 resp = SetOperationModeResponse()
00260 resp.success.data = True
00261 return resp
00262
00263
00264 def sdh_right_init_cb(self, req):
00265 resp = TriggerResponse()
00266 resp.success.data = True
00267 return resp
00268
00269 def sdh_right_stop_cb(self, req):
00270 self.sdh_right_client.cancel_all_goals()
00271 resp = TriggerResponse()
00272 resp.success.data = True
00273 return resp
00274
00275 def sdh_right_recover_cb(self, req):
00276 resp = TriggerResponse()
00277 resp.success.data = True
00278 return resp
00279
00280 def sdh_right_set_operation_mode_cb(self, req):
00281 resp = SetOperationModeResponse()
00282 resp.success.data = True
00283 return resp
00284
00285
00286 def head_init_cb(self, req):
00287 resp = TriggerResponse()
00288 resp.success.data = True
00289 return resp
00290
00291 def head_stop_cb(self, req):
00292 self.head_client.cancel_all_goals()
00293 resp = TriggerResponse()
00294 resp.success.data = True
00295 return resp
00296
00297 def head_recover_cb(self, req):
00298 resp = TriggerResponse()
00299 resp.success.data = True
00300 return resp
00301
00302 def head_set_operation_mode_cb(self, req):
00303 resp = SetOperationModeResponse()
00304 resp.success.data = True
00305 return resp
00306
00307 if __name__ == "__main__":
00308 rospy.init_node('gazebo_services')
00309 gazebo_services()
00310 rospy.loginfo("gazebo_services running")
00311 rospy.spin()
00312