conversions.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Ioan Sucan, Sarah Elliott
00034 
00035 from moveit_commander import MoveItCommanderException
00036 from geometry_msgs.msg import Pose, PoseStamped, Transform, TransformStamped
00037 from moveit_msgs.msg import RobotTrajectory, MultiDOFJointTrajectory, MultiDOFJointTrajectoryPoint
00038 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
00039 import rospy
00040 import tf
00041 
00042 def pose_to_list(pose_msg):
00043     pose = []
00044     pose.append(pose_msg.position.x)
00045     pose.append(pose_msg.position.y)
00046     pose.append(pose_msg.position.z) 
00047     pose.append(pose_msg.orientation.x)
00048     pose.append(pose_msg.orientation.y)
00049     pose.append(pose_msg.orientation.z)
00050     pose.append(pose_msg.orientation.w)
00051     return pose
00052 
00053 def transform_to_list(trf_msg):
00054     trf = []
00055     trf.append(trf_msg.translation.x)
00056     trf.append(trf_msg.translation.y)
00057     trf.append(trf_msg.translation.z) 
00058     trf.append(trf_msg.rotation.x)
00059     trf.append(trf_msg.rotation.y)
00060     trf.append(trf_msg.rotation.z)
00061     trf.append(trf_msg.rotation.w)
00062     return trf
00063 
00064 def list_to_pose_stamped(pose_list, target_frame):
00065     pose_msg = PoseStamped()
00066     if len(pose_list) == 7:
00067         pose_msg.pose.position.x = pose_list[0]
00068         pose_msg.pose.position.y = pose_list[1]
00069         pose_msg.pose.position.z = pose_list[2]
00070         pose_msg.pose.orientation.x = pose_list[3]
00071         pose_msg.pose.orientation.y = pose_list[4]
00072         pose_msg.pose.orientation.z = pose_list[5]
00073         pose_msg.pose.orientation.w = pose_list[6]
00074     elif len(pose_list) == 6: 
00075         pose_msg.pose.position.x = pose_list[0]
00076         pose_msg.pose.position.y = pose_list[1]
00077         pose_msg.pose.position.z = pose_list[2]
00078         q = tf.transformations.quaternion_from_euler(pose_list[3], pose_list[4], pose_list[5])
00079         pose_msg.pose.orientation.x = q[0]
00080         pose_msg.pose.orientation.y = q[1]
00081         pose_msg.pose.orientation.z = q[2]
00082         pose_msg.pose.orientation.w = q[3]
00083     else:
00084         raise MoveItCommanderException("Expected either 6 or 7 elements in list: (x,y,z,r,p,y) or (x,y,z,qx,qy,qz,qw)")
00085     pose_msg.header.frame_id = target_frame
00086     pose_msg.header.stamp = rospy.Time.now()
00087     return pose_msg
00088 
00089 def list_to_transform(trf_list):
00090     trf_msg = Transform()
00091     trf_msg.translation.x = trf_list[0]
00092     trf_msg.translation.y = trf_list[1]
00093     trf_msg.translation.z = trf_list[2]
00094     trf_msg.rotation.x = trf_list[3]
00095     trf_msg.rotation.y = trf_list[4]
00096     trf_msg.rotation.z = trf_list[5]
00097     trf_msg.rotation.w = trf_list[6]
00098     return trf_msg
00099 
00100 def dict_to_trajectory(plan):
00101     plan_msg = RobotTrajectory()
00102     joint_traj = JointTrajectory()
00103     joint_traj.header.frame_id = plan["joint_trajectory"]["frame_id"]
00104     joint_traj.joint_names = plan["joint_trajectory"]["joint_names"]
00105     for point in plan["joint_trajectory"]["points"]:
00106         joint_traj.points.append(JointTrajectoryPoint(
00107                 positions = point["positions"],
00108                 velocities = point["velocities"],
00109                 accelerations = point["accelerations"],
00110                 time_from_start = rospy.Duration().from_sec(point["time_from_start"])))
00111     multi_dof_joint_traj = MultiDOFJointTrajectory()
00112     multi_dof_joint_traj.header.frame_id = plan["multi_dof_joint_trajectory"]["frame_id"]
00113     multi_dof_joint_traj.joint_names = plan["multi_dof_joint_trajectory"]["joint_names"]
00114     for point in plan["multi_dof_joint_trajectory"]["points"]:
00115         multi_dof_joint_traj_point = MultiDOFJointTrajectoryPoint()
00116         for t in point["transforms"]:
00117             multi_dof_joint_traj_point.transforms.append(list_to_transform(t))
00118         multi_dof_joint_traj_point.time_from_start = rospy.Duration().from_sec(point["time_from_start"])
00119         multi_dof_joint_traj.points.append(multi_dof_joint_traj_point)
00120     plan_msg.joint_trajectory = joint_traj
00121     plan_msg.multi_dof_joint_trajectory = multi_dof_joint_traj
00122     return plan_msg    
00123 
00124 def trajectory_to_dict(plan_msg):
00125     plan = {}
00126     plan["joint_trajectory"] = {}
00127     plan["joint_trajectory"]["frame_id"] = plan_msg.joint_trajectory.header.frame_id
00128     plan["joint_trajectory"]["joint_names"] = plan_msg.joint_trajectory.joint_names
00129     joint_trajectory_points = []
00130     for p in plan_msg.joint_trajectory.points:
00131         point = {}
00132         point["positions"] = p.positions
00133         point["velocities"] = p.velocities
00134         point["accelerations"] = p.accelerations
00135         point["time_from_start"] = p.time_from_start.to_sec()
00136         joint_trajectory_points.append(point)
00137     plan["joint_trajectory"]["points"] = joint_trajectory_points
00138 
00139     plan["multi_dof_joint_trajectory"] = {}
00140     plan["multi_dof_joint_trajectory"]["frame_id"] = plan_msg.multi_dof_joint_trajectory.header.frame_id
00141     plan["multi_dof_joint_trajectory"]["joint_names"] = plan_msg.multi_dof_joint_trajectory.joint_names
00142     multi_dof_joint_trajectory_points = []
00143     for p in plan_msg.multi_dof_joint_trajectory.points:
00144         point = {}
00145         point["transforms"] = []
00146         for t in p.transforms:
00147             point["transforms"].append(transform_to_list(t))
00148         point["time_from_start"] = p.time_from_start.to_sec()
00149         multi_dof_joint_trajectory_points.append(point)
00150     plan["multi_dof_joint_trajectory"]["points"] = multi_dof_joint_trajectory_points
00151     return plan


moveit_commander
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:24:45