goal_tool_orientation.cpp
Go to the documentation of this file.
00001 
00026 #include "constrained_ik/constrained_ik.h"
00027 #include "constrained_ik/constraints/goal_tool_orientation.h"
00028 #include <ros/ros.h>
00029 #include <pluginlib/class_list_macros.h>
00030 PLUGINLIB_EXPORT_CLASS(constrained_ik::constraints::GoalToolOrientation, constrained_ik::Constraint)
00031 
00032 namespace constrained_ik
00033 {
00034 namespace constraints
00035 {
00036 
00037 using namespace Eigen;
00038 
00039 // initialize limits/tolerances to default values
00040 GoalToolOrientation::GoalToolOrientation() : GoalOrientation()
00041 {
00042 }
00043 
00044 constrained_ik::ConstraintResults GoalToolOrientation::evalConstraint(const SolverState &state) const
00045 {
00046   constrained_ik::ConstraintResults output;
00047   GoalOrientation::GoalOrientationData cdata(state);
00048 
00049   output.error = calcError(cdata);
00050   output.jacobian = calcJacobian(cdata);
00051   output.status = checkStatus(cdata);
00052 
00053   return output;
00054 }
00055 
00056 Eigen::VectorXd GoalToolOrientation::calcError(const GoalOrientation::GoalOrientationData &cdata) const
00057 {
00058   //rotate jacobian into tool frame by premultiplying by otR.transpose()
00059   Vector3d err = cdata.state_.pose_estimate.rotation().transpose() * calcAngleError(cdata.state_.pose_estimate, cdata.state_.goal);
00060 
00061   err = err.cwiseProduct(weight_);
00062   ROS_ASSERT(err.rows() == 3);
00063   return err;
00064 }
00065 
00066 // translate cartesian errors into joint-space errors
00067 Eigen::MatrixXd GoalToolOrientation::calcJacobian(const GoalOrientation::GoalOrientationData &cdata) const
00068 {
00069   MatrixXd tmpJ;
00070   if (!ik_->getKin().calcJacobian(cdata.state_.joints, tmpJ))
00071     throw std::runtime_error("Failed to calculate Jacobian");
00072 
00073   //rotate jacobian into tool frame by premultiplying by otR.transpose()
00074   MatrixXd J = cdata.state_.pose_estimate.rotation().transpose() * tmpJ.bottomRows(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 } // namespace constraints
00085 } // namespace constrained_ik
00086 


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