goal_position.cpp
Go to the documentation of this file.
00001 
00026 #include "constrained_ik/constrained_ik.h"
00027 #include "constrained_ik/constraints/goal_position.h"
00028 #include <ros/assert.h>
00029 #include <pluginlib/class_list_macros.h>
00030 PLUGINLIB_EXPORT_CLASS(constrained_ik::constraints::GoalPosition, constrained_ik::Constraint)
00031 
00032 const double DEFAULT_POSITION_TOLERANCE = 0.001; 
00034 namespace constrained_ik
00035 {
00036 namespace constraints
00037 {
00038 
00039 using namespace Eigen;
00040 
00041 // initialize limits/tolerances to default values
00042 GoalPosition::GoalPosition() : Constraint(), pos_err_tol_(DEFAULT_POSITION_TOLERANCE), weight_(Vector3d::Ones())
00043 {
00044 }
00045 
00046 constrained_ik::ConstraintResults GoalPosition::evalConstraint(const SolverState &state) const
00047 {
00048   constrained_ik::ConstraintResults output;
00049   GoalPosition::GoalPositionData cdata(state);
00050 
00051   output.error = calcError(cdata);
00052   output.jacobian = calcJacobian(cdata);
00053   output.status = checkStatus(cdata);
00054 
00055   return output;
00056 }
00057 
00058 Eigen::VectorXd GoalPosition::calcError(const GoalPosition::GoalPositionData &cdata) const
00059 {
00060   Vector3d goalPos = cdata.state_.goal.translation();
00061   Vector3d estPos  = cdata.state_.pose_estimate.translation();
00062   Vector3d err = (goalPos - estPos).cwiseProduct(weight_);
00063 
00064   ROS_ASSERT( err.rows() == 3 );
00065   return err;
00066 }
00067 
00068 // translate cartesian errors into joint-space errors
00069 Eigen::MatrixXd GoalPosition::calcJacobian(const GoalPosition::GoalPositionData &cdata) const
00070 {
00071   MatrixXd tmpJ;
00072   if (!ik_->getKin().calcJacobian(cdata.state_.joints, tmpJ))
00073     throw std::runtime_error("Failed to calculate Jacobian");
00074   MatrixXd  J = tmpJ.topRows(3);
00075 
00076   // weight each row of J
00077   for (size_t ii=0; ii<3; ++ii)
00078       J.row(ii) *= weight_(ii);
00079 
00080   ROS_ASSERT( J.rows() == 3);
00081   return J;
00082 }
00083 
00084 double GoalPosition::calcDistance(const Eigen::Affine3d &p1, const Eigen::Affine3d &p2)
00085 {
00086   return (p2.translation() - p1.translation()).norm();
00087 }
00088 
00089 bool GoalPosition::checkStatus(const GoalPosition::GoalPositionData &cdata) const
00090 {
00091   // check to see if we've reached the goal position
00092   if (cdata.pos_err_ < pos_err_tol_)
00093     return true;
00094 
00095   return false;
00096 }
00097 
00098 void GoalPosition::loadParameters(const XmlRpc::XmlRpcValue &constraint_xml)
00099 {
00100   XmlRpc::XmlRpcValue local_xml = constraint_xml;
00101   double pos_tol;
00102   if (getParam(local_xml, "position_tolerance", pos_tol))
00103   {
00104     setTolerance(pos_tol);
00105   }
00106   else
00107   {
00108     ROS_WARN("Goal Position: Unable to retrieve position_tolerance member, default parameter will be used.");
00109   }
00110 
00111   Eigen::VectorXd weights;
00112   if (getParam(local_xml, "weights", weights))
00113   {
00114     if (weights.size() == 3)
00115     {
00116       setWeight(weights);
00117     }
00118     else
00119     {
00120       ROS_WARN("Gool Position: Unable to add weights member, value must be a array of size 3.");
00121     }
00122   }
00123   else
00124   {
00125     ROS_WARN("Gool Position: Unable to retrieve weights member, default parameter will be used.");
00126   }
00127 
00128   bool debug;
00129   if (getParam(local_xml, "debug", debug))
00130   {
00131     setDebug(debug);
00132   }
00133   else
00134   {
00135     ROS_WARN("Goal Position: Unable to retrieve debug member, default parameter will be used.");
00136   }
00137 }
00138 
00139 GoalPosition::GoalPositionData::GoalPositionData(const SolverState &state): ConstraintData(state)
00140 {
00141   pos_err_ = calcDistance(state.goal, state.pose_estimate);
00142 }
00143 
00144 } // namespace constraints
00145 } // namespace constrained_ik
00146 


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Sat Jun 8 2019 19:23:45