test_move_circ.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import math
00019 import rospy
00020 import actionlib
00021 
00022 from cob_cartesian_controller.msg import CartesianControllerAction, CartesianControllerGoal
00023 from cob_cartesian_controller.msg import Profile
00024 
00025 if __name__ == '__main__':
00026     rospy.init_node('test_move_circ')
00027     action_name = rospy.get_namespace()+'cartesian_trajectory_action'
00028     client = actionlib.SimpleActionClient(action_name, CartesianControllerAction)
00029     rospy.logwarn("Waiting for ActionServer: %s", action_name)
00030     client.wait_for_server()
00031     rospy.logwarn("...done")
00032 
00033     # Fill in the goal here
00034     goal = CartesianControllerGoal()
00035 
00036     goal.move_type = CartesianControllerGoal.CIRC
00037     goal.move_circ.pose_center.position.x = 0.0
00038     goal.move_circ.pose_center.position.y = 0.7
00039     goal.move_circ.pose_center.position.z = 1.0
00040     goal.move_circ.pose_center.orientation.x = 0.0
00041     goal.move_circ.pose_center.orientation.y = 0.0
00042     goal.move_circ.pose_center.orientation.z = 0.0
00043     goal.move_circ.pose_center.orientation.w = 1.0
00044     goal.move_circ.frame_id = 'world'
00045 
00046     goal.move_circ.start_angle = 0 * math.pi / 180.0
00047     goal.move_circ.end_angle = 90 * math.pi / 180.0
00048     goal.move_circ.radius = 0.3
00049 
00050     goal.profile.vel = 0.1
00051     goal.profile.accl = 0.2
00052     goal.profile.profile_type = Profile.SINOID
00053 
00054     #print goal
00055 
00056     # Send the goal
00057     client.send_goal(goal)
00058     client.wait_for_result()


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Jun 6 2019 21:19:40