Gazebo Msgs

API Reference

11.0.0~pre1
Pose.hh
Go to the documentation of this file.
1/*
2 * Copyright (C) 2023 Open Source Robotics Foundation
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *
16 */
17#ifndef GZ_MSGS_CONVERT_POSE_HH_
18#define GZ_MSGS_CONVERT_POSE_HH_
19
20#include <gz/msgs/config.hh>
23
24// Message Headers
25#include "gz/msgs/quaternion.pb.h"
26#include "gz/msgs/pose.pb.h"
27
28// Data Headers
29#include <gz/math/Pose3.hh>
30
31namespace gz::msgs {
32// Inline bracket to help doxygen filtering.
33inline namespace GZ_MSGS_VERSION_NAMESPACE {
34
36inline void Set(gz::msgs::Pose *_msg, const gz::math::Pose3d &_data)
37{
38 Set(_msg->mutable_position(), _data.Pos());
39 Set(_msg->mutable_orientation(), _data.Rot());
40}
41
42inline void Set(gz::math::Pose3d *_data, const gz::msgs::Pose &_msg)
43{
45 gz::math::Quaterniond orientation;
46
47 if (_msg.has_position())
48 pos = Convert(_msg.position());
49
50 // This bit is critical. If orientation hasn't been set in the message,
51 // then we want the quaternion to default to identity.
52 if (_msg.has_orientation())
53 orientation = Convert(_msg.orientation());
54
55 _data->Set(pos, orientation);
56}
57
58inline gz::msgs::Pose Convert(const gz::math::Pose3d &_data)
59{
60 gz::msgs::Pose ret;
61 Set(&ret, _data);
62 return ret;
63}
64
65inline gz::math::Pose3d Convert(const gz::msgs::Pose &_msg)
66{
68 Set(&ret, _msg);
69 return ret;
70}
71} // namespce
72} // namespace gz::msgs
73
74#endif // GZ_MSGS_CONVERT_VECTOR3_HH_