Program Listing for File chain3d.hpp

Return to documentation for file (/tmp/ws/src/robot_calibration/robot_calibration/include/robot_calibration/models/chain3d.hpp)

/*
 * Copyright (C) 2022 Michael Ferguson
 * Copyright (C) 2015 Fetch Robotics Inc.
 * Copyright (C) 2013-2014 Unbounded Robotics Inc.
 *
 * 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.
 */

// Author: Michael Ferguson

#ifndef ROBOT_CALIBRATION_MODELS_CHAIN3D_HPP
#define ROBOT_CALIBRATION_MODELS_CHAIN3D_HPP

#include <string>
#include <kdl/chain.hpp>
#include <kdl/tree.hpp>
#include <robot_calibration/optimization/offsets.hpp>

#include <geometry_msgs/msg/point_stamped.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <robot_calibration_msgs/msg/calibration_data.hpp>

namespace robot_calibration
{

class Chain3dModel
{
public:
  Chain3dModel(const std::string& name, KDL::Tree model, std::string root, std::string tip);
  virtual ~Chain3dModel() {}

  virtual std::vector<geometry_msgs::msg::PointStamped> project(
    const robot_calibration_msgs::msg::CalibrationData& data,
    const OptimizationOffsets& offsets);

  KDL::Frame getChainFK(const OptimizationOffsets& offsets,
                        const sensor_msgs::msg::JointState& state);

  virtual std::string getName() const;

  virtual std::string getType() const;

private:
  KDL::Chain chain_;

protected:
  std::string root_;
  std::string tip_;
  std::string name_;
};

KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z);

void axis_magnitude_from_rotation(const KDL::Rotation& r, double& x, double& y, double& z);

}  // namespace robot_calibration

#endif  // ROBOT_CALIBRATION_MODELS_CHAIN3D_HPP