goal_position.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2013, Southwest Research Institute
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 #include "constrained_ik/constrained_ik.h"
00020 #include "constrained_ik/constraints/goal_position.h"
00021 #include <ros/assert.h>
00022 
00023 namespace constrained_ik
00024 {
00025 namespace constraints
00026 {
00027 
00028 using namespace Eigen;
00029 
00030 // initialize limits/tolerances to default values
00031 GoalPosition::GoalPosition() : Constraint(), pos_err_tol_(0.001), pos_err_(0.0), weight_(Vector3d::Ones())
00032 {
00033 }
00034 
00035 Eigen::VectorXd GoalPosition::calcError()
00036 {
00037   Vector3d goalPos = state_.goal.translation();
00038   Vector3d estPos  = state_.pose_estimate.translation();
00039   Vector3d err = (goalPos - estPos).cwiseProduct(weight_);
00040 
00041   ROS_ASSERT( err.rows() == 3 );
00042   return err;
00043 }
00044 
00045 // translate cartesian errors into joint-space errors
00046 Eigen::MatrixXd GoalPosition::calcJacobian()
00047 {
00048   MatrixXd tmpJ;
00049   if (!ik_->getKin().calcJacobian(state_.joints, tmpJ))
00050     throw std::runtime_error("Failed to calculate Jacobian");
00051   MatrixXd  J = tmpJ.topRows(3);
00052 
00053   // weight each row of J
00054   for (size_t ii=0; ii<3; ++ii)
00055       J.row(ii) *= weight_(ii);
00056 
00057   ROS_ASSERT( J.rows() == 3);
00058   return J;
00059 }
00060 
00061 double GoalPosition::calcDistance(const Eigen::Affine3d &p1, const Eigen::Affine3d &p2)
00062 {
00063   return (p2.translation() - p1.translation()).norm();
00064 }
00065 
00066 bool GoalPosition::checkStatus() const
00067 {
00068   // check to see if we've reached the goal position
00069   if (pos_err_ < pos_err_tol_)
00070     return true;
00071 
00072   return Constraint::checkStatus();
00073 }
00074 
00075 void GoalPosition::reset()
00076 {
00077   Constraint::reset();
00078   pos_err_ = 0;
00079 }
00080 
00081 void GoalPosition::update(const SolverState &state)
00082 {
00083   Constraint::update(state);
00084 
00085   pos_err_ = calcDistance(state.goal, state.pose_estimate);
00086 }
00087 
00088 } // namespace constraints
00089 } // namespace constrained_ik
00090 


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Mon Oct 6 2014 00:52:26