joint_trajectory_pt.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2014, Dan Solomon
00005  *
00006  * Licensed under the Apache License, Version 2.0 (the "License");
00007  * you may not use this file except in compliance with the License.
00008  * You may obtain a copy of the License at
00009  *
00010  * http://www.apache.org/licenses/LICENSE-2.0
00011  *
00012  * Unless required by applicable law or agreed to in writing, software
00013  * distributed under the License is distributed on an "AS IS" BASIS,
00014  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015  * See the License for the specific language governing permissions and
00016  * limitations under the License.
00017  */
00018 /*
00019  * joint_trajectory_pt.cpp
00020  *
00021  *  Created on: Oct 3, 2014
00022  *      Author: Dan Solomon
00023  */
00024 
00025 #include <console_bridge/console.h>
00026 #include "descartes_trajectory/joint_trajectory_pt.h"
00027 
00028 #define NOT_IMPLEMENTED_ERR(ret)                                                                                       \
00029   logError("%s not implemented", __PRETTY_FUNCTION__);                                                                 \
00030   return ret;
00031 
00032 // Utility function to unpack joint bounds from a TolerancedJointValue struct
00033 // Note that this does not clear the existing vectors.
00034 static void unpackTolerancedJoints(const std::vector<descartes_trajectory::TolerancedJointValue> &tolerances,
00035                                    std::vector<double> &lower, std::vector<double> &nominal, std::vector<double> &upper)
00036 {
00037   lower.reserve(tolerances.size());
00038   nominal.reserve(tolerances.size());
00039   upper.reserve(tolerances.size());
00040 
00041   for (std::size_t i = 0; i < tolerances.size(); ++i)
00042   {
00043     lower.push_back(tolerances[i].lower);
00044     nominal.push_back(tolerances[i].nominal);
00045     upper.push_back(tolerances[i].upper);
00046   }
00047 }
00048 
00049 using namespace descartes_core;
00050 namespace descartes_trajectory
00051 {
00052 JointTrajectoryPt::JointTrajectoryPt(const descartes_core::TimingConstraint &timing)
00053   : descartes_core::TrajectoryPt(timing), tool_(Eigen::Affine3d::Identity()), wobj_(Eigen::Affine3d::Identity())
00054 {
00055 }
00056 
00057 JointTrajectoryPt::JointTrajectoryPt(const std::vector<TolerancedJointValue> &joints, const Frame &tool,
00058                                      const Frame &wobj, const descartes_core::TimingConstraint &timing)
00059   : descartes_core::TrajectoryPt(timing), tool_(tool), wobj_(wobj)
00060 {
00061   unpackTolerancedJoints(joints, lower_, nominal_, upper_);
00062 }
00063 
00064 JointTrajectoryPt::JointTrajectoryPt(const std::vector<TolerancedJointValue> &joints,
00065                                      const descartes_core::TimingConstraint &timing)
00066   : descartes_core::TrajectoryPt(timing), tool_(Eigen::Affine3d::Identity()), wobj_(Eigen::Affine3d::Identity())
00067 {
00068   unpackTolerancedJoints(joints, lower_, nominal_, upper_);
00069 }
00070 
00071 JointTrajectoryPt::JointTrajectoryPt(const std::vector<double> &joints, const descartes_core::TimingConstraint &timing)
00072   : nominal_(joints)
00073   , lower_(joints)
00074   , upper_(joints)
00075   , descartes_core::TrajectoryPt(timing)
00076   , tool_(Eigen::Affine3d::Identity())
00077   , wobj_(Eigen::Affine3d::Identity())
00078 {
00079 }
00080 
00081 bool JointTrajectoryPt::getClosestCartPose(const std::vector<double> &seed_state, const RobotModel &model,
00082                                            Eigen::Affine3d &pose) const
00083 {
00084   NOT_IMPLEMENTED_ERR(false)
00085 }
00086 
00087 bool JointTrajectoryPt::getNominalCartPose(const std::vector<double> &seed_state, const RobotModel &model,
00088                                            Eigen::Affine3d &pose) const
00089 {
00090   return model.getFK(nominal_, pose);
00091 }
00092 
00093 void JointTrajectoryPt::getCartesianPoses(const RobotModel &model, EigenSTL::vector_Affine3d &poses) const
00094 {
00095   poses.clear();
00096 }
00097 
00098 bool JointTrajectoryPt::getClosestJointPose(const std::vector<double> &seed_state, const RobotModel &model,
00099                                             std::vector<double> &joint_pose) const
00100 {
00101   if (nominal_.empty())
00102   {
00103     return false;
00104   }
00105   else
00106   {
00107     return getNominalJointPose(seed_state, model, joint_pose);
00108   }
00109 }
00110 
00111 bool JointTrajectoryPt::getNominalJointPose(const std::vector<double> &seed_state, const RobotModel &model,
00112                                             std::vector<double> &joint_pose) const
00113 {
00114   joint_pose.assign(nominal_.begin(), nominal_.end());
00115   return true;
00116 }
00117 
00118 void JointTrajectoryPt::getJointPoses(const RobotModel &model, std::vector<std::vector<double> > &joint_poses) const
00119 {
00120   std::vector<double> empty_seed;
00121   joint_poses.resize(1);
00122   getNominalJointPose(empty_seed, model, joint_poses[0]);
00123 }
00124 
00125 bool JointTrajectoryPt::isValid(const RobotModel &model) const
00126 {
00127   return model.isValid(lower_) && model.isValid(upper_);
00128 }
00129 
00130 bool JointTrajectoryPt::setDiscretization(const std::vector<double> &discretization)
00131 {
00132   if (discretization.size() != 1 || discretization.size() != nominal_.size())
00133   {
00134     logError("discretization must be size 1 or same size as joint count.");
00135     return false;
00136   }
00137 
00138   if (discretization.size() == 1)
00139   {
00140     discretization_ = std::vector<double>(nominal_.size(), discretization[0]);
00141     return true;
00142   }
00143 
00144   /* Do not copy discretization values until all values are confirmed */
00145   for (size_t ii = 0; ii < discretization.size(); ++ii)
00146   {
00147     if (discretization[ii] < 0. || discretization[ii] > (upper_[ii] - lower_[ii]))
00148     {
00149       logError("discretization value out of range.");
00150       return false;
00151     }
00152   }
00153 
00154   discretization_ = discretization;
00155 
00156   return true;
00157 }
00158 
00159 void JointTrajectoryPt::setJoints(const std::vector<TolerancedJointValue> &joints)
00160 {
00161   lower_.clear();
00162   nominal_.clear();
00163   upper_.clear();
00164   unpackTolerancedJoints(joints, lower_, nominal_, upper_);
00165 }
00166 
00167 } /* namespace descartes_trajectory */


descartes_trajectory
Author(s): Jorge Nicho
autogenerated on Thu Jun 6 2019 21:36:04