test_move_circ_interface.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import math
19 import rospy
20 
21 from geometry_msgs.msg import Pose
22 from cob_cartesian_controller.msg import Profile
23 import simple_cartesian_interface as sci
24 
25 if __name__ == '__main__':
26  rospy.init_node('test_move_circ_interface')
27 
28  pose = sci.gen_pose(pos=[0.0, 0.7, 1.0], rpy=[0.0, 0.0, 0.0])
29  start_angle = 0.0 * math.pi / 180.0
30  end_angle = 90.0 * math.pi / 180.0
31  profile = Profile()
32  profile.vel = 0.2
33  profile.accl = 0.1
34  #profile.profile_type = Profile.SINOID
35  profile.profile_type = Profile.RAMP
36 
37  success, message = sci.move_circ(pose, "world", start_angle, end_angle, 0.3, profile)
38  if success:
39  rospy.loginfo(message)
40  else:
41  rospy.logerr(message)


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Apr 8 2021 02:40:13