pose.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Software License Agreement (BSD License) *
3  * Copyright (C) 2016 by Markus Bader <markus.bader@tuwien.ac.at> *
4  * *
5  * Redistribution and use in source and binary forms, with or without *
6  * modification, are permitted provided that the following conditions *
7  * are met: *
8  * *
9  * 1. Redistributions of source code must retain the above copyright *
10  * notice, this list of conditions and the following disclaimer. *
11  * 2. Redistributions in binary form must reproduce the above copyright *
12  * notice, this list of conditions and the following disclaimer in *
13  * the documentation and/or other materials provided with the *
14  * distribution. *
15  * 3. Neither the name of the copyright holder nor the names of its *
16  * contributors may be used to endorse or promote products derived *
17  * from this software without specific prior written permission. *
18  * *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT *
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS *
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE *
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, *
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, *
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; *
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY *
29  * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE *
30  * POSSIBILITY OF SUCH DAMAGE. *
31  ***************************************************************************/
32 
33 #include <tuw_geometry_msgs/pose.h>
34 #include <memory.h>
35 
36 using namespace tuw::ros_msgs;
37 
39 
40 };
41 
42 Pose::Pose(double x, double y, double z, double roll, double pitch, double yaw)
43 {
44  set(x, y, z, roll, pitch, yaw);
45 }
46 
47 Pose &Pose::set(double x, double y, double z, double roll, double pitch, double yaw)
48 {
49  setXYZ(x, y, z);
50  setRPY(roll, pitch, yaw);
51  return *this;
52 }
53 
54 Pose &Pose::setXYZ(double x, double y, double z)
55 {
56  position.x = x, position.y = y, position.z = z;
57  return *this;
58 }
59 Pose &Pose::setOrientation(double x, double y, double z, double w)
60 {
61  orientation.x = x, orientation.y = y, orientation.z = z, orientation.w = w;
62  return *this;
63 }
64 Pose &Pose::setRPY(double roll, double pitch, double yaw)
65 {
66  double halfYaw = double(yaw) * double(0.5), halfPitch = double(pitch) * double(0.5),
67  halfRoll = double(roll) * double(0.5);
68  double cosYaw = cos(halfYaw), sinYaw = sin(halfYaw), cosPitch = cos(halfPitch), sinPitch = sin(halfPitch),
69  cosRoll = cos(halfRoll), sinRoll = sin(halfRoll);
70  setOrientation(sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw, // x
71  cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw, // y
72  cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw, // z
73  cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw); // formerly yzx
74  return *this;
75 }
77 {
78  geometry_msgs::PosePtr p = geometry_msgs::PosePtr(new geometry_msgs::Pose);
79  Set(p, *this);
80  return p;
81 }
82 void tuw::SetPositionXYZ(geometry_msgs::PosePtr &pose, double x, double y, double z)
83 {
84  pose->position.x = x, pose->position.y = y, pose->position.z = z;
85 }
86 void tuw::SetOrientation(geometry_msgs::PosePtr &pose, double x, double y, double z, double w)
87 {
88  pose->orientation.x = x, pose->orientation.y = y, pose->orientation.z = z, pose->orientation.w = w;
89 }
90 void tuw::SetRPY(geometry_msgs::PosePtr &pose, double roll, double pitch, double yaw)
91 {
92  double halfYaw = double(yaw) * double(0.5), halfPitch = double(pitch) * double(0.5),
93  halfRoll = double(roll) * double(0.5);
94  double cosYaw = cos(halfYaw), sinYaw = sin(halfYaw), cosPitch = cos(halfPitch), sinPitch = sin(halfPitch),
95  cosRoll = cos(halfRoll), sinRoll = sin(halfRoll);
96  pose->orientation.x = sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw; // x
97  pose->orientation.y = cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw; // y
98  pose->orientation.z = cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw; // z
99  pose->orientation.w = cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw; // formerly yzx
100 }
101 void tuw::Set(geometry_msgs::PosePtr &pose, double x, double y, double z, double roll, double pitch, double yaw)
102 {
103  SetPositionXYZ(pose, x, y, z), SetRPY(pose, roll, pitch, yaw);
104 }
105 void tuw::Set(geometry_msgs::PosePtr &des, const Pose &src)
106 {
107  SetPositionXYZ(des, src.position.x, src.position.y, src.position.z);
108  SetOrientation(des, src.orientation.x, src.orientation.y, src.orientation.z, src.orientation.w);
109 }
pose.h
tuw::ros_msgs::PosePtr
boost::shared_ptr< Pose > PosePtr
Definition: pose.h:104
tuw::Set
void Set(geometry_msgs::PosePtr &pose, double x, double y, double z, double roll, double pitch, double yaw)
Definition: pose.cpp:101
tuw::ros_msgs
Definition: point.h:71
tuw::ros_msgs::Pose
Definition: pose.h:108
tuw::ros_msgs::Pose::setRPY
Pose & setRPY(double roll, double pitch, double yaw)
Definition: pose.cpp:64
tuw::SetRPY
void SetRPY(geometry_msgs::PosePtr &pose, double roll, double pitch, double yaw)
Definition: pose.cpp:90
tuw::SetOrientation
void SetOrientation(geometry_msgs::PosePtr &pose, double x, double y, double z, double w)
Definition: pose.cpp:86
tuw::ros_msgs::Pose::setOrientation
Pose & setOrientation(double x, double y, double z, double w)
Definition: pose.cpp:59
tuw::ros_msgs::Pose::create
geometry_msgs::PosePtr create()
Definition: pose.cpp:76
tuw::ros_msgs::Pose::setXYZ
Pose & setXYZ(double x, double y, double z)
Definition: pose.cpp:54
tuw::SetPositionXYZ
void SetPositionXYZ(geometry_msgs::PosePtr &pose, double x, double y, double z)
Definition: pose.cpp:82
tuw::ros_msgs::Pose::Pose
Pose()
Definition: pose.cpp:38
tuw::ros_msgs::Pose::set
Pose & set(double x, double y, double z, double roll, double pitch, double yaw)
Definition: pose.cpp:47


tuw_geometry_msgs
Author(s): Markus Bader
autogenerated on Wed Aug 10 2022 02:11:56