trajectory_unwrap.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above \
14 
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Melonee Wise
36  *********************************************************************/
37 
38 #ifndef TRAJECTORY_UNWRAP_H_
39 #define TRAJECTORY_UNWRAP_H_
40 
41 #include <angles/angles.h>
42 #include <urdf/model.h>
43 #include <urdf/joint.h>
44 #include <trajectory_msgs/JointTrajectory.h>
45 
47 {
48 
49 void unwrap(urdf::Model &robot_model, const trajectory_msgs::JointTrajectory& traj_in,
50  trajectory_msgs::JointTrajectory& traj_out)
51 {
52  //defualt result
53  traj_out = traj_in;
54 
55  int num_jnts = traj_in.joint_names.size();
56  int traj_pnts = traj_in.points.size();
58 
59  for(int i=0; i<num_jnts; i++)
60  {
61  joint = robot_model.getJoint(traj_in.joint_names[i]);
62  if(joint->type == urdf::Joint::REVOLUTE)
63  {
64  for(int j=1; j<traj_pnts; j++)
65  {
66  double diff;
67 
68  angles::shortest_angular_distance_with_limits(traj_out.points[j-1].positions[i], traj_out.points[j].positions[i], joint->limits->lower, joint->limits->upper, diff);
69  traj_out.points[j].positions[i] = traj_out.points[j-1].positions[i] + diff;
70  }
71  }
72  if(joint->type == urdf::Joint::CONTINUOUS)
73  {
74  for(int j=1; j<traj_pnts; j++)
75  {
76  traj_out.points[j].positions[i] = traj_out.points[j-1].positions[i] + angles::shortest_angular_distance(traj_out.points[j-1].positions[i],traj_out.points[j].positions[i]);
77  }
78  }
79  }
80 }
81 }
82 #endif
void unwrap(urdf::Model &robot_model, const trajectory_msgs::JointTrajectory &traj_in, trajectory_msgs::JointTrajectory &traj_out)
def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit)
def shortest_angular_distance(from_angle, to_angle)


pr2_arm_move_ik
Author(s): Wim Meeusen, Melonee Wise
autogenerated on Fri Jun 7 2019 22:06:41