Program Listing for File quaternion_operation.h

Return to documentation for file (include/quaternion_operation/quaternion_operation.h)

// Copyright (c) 2019 OUXT Polaris
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef QUATERNION_OPERATION__QUATERNION_OPERATION_H_
#define QUATERNION_OPERATION__QUATERNION_OPERATION_H_

// headers in ROS
#include <tf2/LinearMath/Matrix3x3.h>

#include <geometry_msgs/msg/quaternion.hpp>
#include <geometry_msgs/msg/vector3.hpp>

// headers in Eigen
#define EIGEN_MPL2_ONLY
#include <Eigen/Core>
#include <Eigen/Geometry>

geometry_msgs::msg::Quaternion operator+(
  geometry_msgs::msg::Quaternion quat1, geometry_msgs::msg::Quaternion quat2);

geometry_msgs::msg::Quaternion operator*(
  geometry_msgs::msg::Quaternion quat1, geometry_msgs::msg::Quaternion quat2);

namespace quaternion_operation
{
geometry_msgs::msg::Quaternion convertEulerAngleToQuaternion(geometry_msgs::msg::Vector3 euler);

Eigen::Matrix3d getRotationMatrix(geometry_msgs::msg::Quaternion quat);

geometry_msgs::msg::Vector3 convertQuaternionToEulerAngle(geometry_msgs::msg::Quaternion quat);

bool equals(double a, double b);

bool equals(geometry_msgs::msg::Quaternion quat1, geometry_msgs::msg::Quaternion quat2);

Eigen::MatrixXd convertToEigenMatrix(geometry_msgs::msg::Quaternion quat);

geometry_msgs::msg::Quaternion conjugate(geometry_msgs::msg::Quaternion quat1);

geometry_msgs::msg::Quaternion rotation(
  geometry_msgs::msg::Quaternion from, geometry_msgs::msg::Quaternion rotation);

geometry_msgs::msg::Quaternion getRotation(
  geometry_msgs::msg::Quaternion from, geometry_msgs::msg::Quaternion to);

geometry_msgs::msg::Quaternion slerp(
  geometry_msgs::msg::Quaternion quat1, geometry_msgs::msg::Quaternion quat2, double t);
}  // namespace quaternion_operation

#endif  // QUATERNION_OPERATION__QUATERNION_OPERATION_H_