00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include "planning_environment/util/kinematic_state_constraint_evaluator.h"
00038 #include <geometric_shapes/shape_operations.h>
00039 #include <tf/transform_datatypes.h>
00040 #include <angles/angles.h>
00041 #include <cassert>
00042
00043 bool planning_environment::JointConstraintEvaluator::use(const ros::Message *kc)
00044 {
00045 const motion_planning_msgs::JointConstraint *jc = dynamic_cast<const motion_planning_msgs::JointConstraint*>(kc);
00046 if (jc)
00047 return use(*jc);
00048 else
00049 return false;
00050 }
00051
00052 bool planning_environment::JointConstraintEvaluator::use(const motion_planning_msgs::JointConstraint &jc)
00053 {
00054 m_jc = jc;
00055 return true;
00056 }
00057
00058 bool planning_environment::JointConstraintEvaluator::decide(const planning_models::KinematicState* state,
00059 bool verbose) const
00060 {
00061 std::vector<double> cur_joint_values;
00062 const planning_models::KinematicState::JointState* joint = state->getJointState(m_jc.joint_name);
00063 if(!joint) {
00064 ROS_WARN_STREAM("No joint in state with name " << m_jc.joint_name);
00065 }
00066 cur_joint_values = joint->getJointStateValues();
00067
00068 if(cur_joint_values.size() == 0) {
00069 ROS_WARN_STREAM("Trying to decide joint with no value " << joint->getName());
00070 }
00071 if(cur_joint_values.size() > 1) {
00072 ROS_WARN_STREAM("Trying to decide joint value with more than one value " << joint->getName());
00073 }
00074
00075 double current_joint_position = cur_joint_values[0];
00076 double dif;
00077
00078 const planning_models::KinematicModel::RevoluteJointModel *revolute_joint = dynamic_cast<const planning_models::KinematicModel::RevoluteJointModel*>(joint->getJointModel());
00079
00080 if(revolute_joint && revolute_joint->continuous_)
00081 dif = angles::shortest_angular_distance(m_jc.position,current_joint_position);
00082 else
00083 dif = current_joint_position - m_jc.position;
00084
00085 if(verbose)
00086 ROS_DEBUG("Joint name:%s, value: %f, Constraint: %f, tolerance_above: %f, tolerance_below: %f",joint->getName().c_str(),current_joint_position,m_jc.position,m_jc.tolerance_above,m_jc.tolerance_below);
00087 if (dif > m_jc.tolerance_above || dif < - m_jc.tolerance_below)
00088 {
00089 if(verbose) {
00090 ROS_INFO("Constraint violated:: Joint name:%s, value: %f, Constraint: %f, tolerance_above: %f, tolerance_below: %f",joint->getName().c_str(),current_joint_position,m_jc.position,m_jc.tolerance_above,m_jc.tolerance_below);
00091 }
00092 return false;
00093 }
00094 return true;
00095 }
00096
00097 void planning_environment::JointConstraintEvaluator::clear(void)
00098 {
00099 }
00100
00101 const motion_planning_msgs::JointConstraint& planning_environment::JointConstraintEvaluator::getConstraintMessage(void) const
00102 {
00103 return m_jc;
00104 }
00105
00106 void planning_environment::JointConstraintEvaluator::print(std::ostream &out) const
00107 {
00108 if (m_joint)
00109 {
00110 out << "Joint constraint for joint " << m_jc.joint_name << ": " << std::endl;
00111 out << " value = ";
00112 out << m_jc.position << "; ";
00113 out << " tolerance below = ";
00114 out << m_jc.tolerance_below << "; ";
00115 out << " tolerance above = ";
00116 out << m_jc.tolerance_above << "; ";
00117 out << std::endl;
00118 }
00119 else
00120 out << "No constraint" << std::endl;
00121 }
00122
00123 bool planning_environment::PositionConstraintEvaluator::use(const ros::Message *kc)
00124 {
00125 const motion_planning_msgs::PositionConstraint *pc = dynamic_cast<const motion_planning_msgs::PositionConstraint*>(kc);
00126 if (pc)
00127 return use(*pc);
00128 else
00129 return false;
00130 }
00131
00132 bool planning_environment::OrientationConstraintEvaluator::use(const ros::Message *kc)
00133 {
00134 const motion_planning_msgs::OrientationConstraint *pc = dynamic_cast<const motion_planning_msgs::OrientationConstraint*>(kc);
00135 if (pc)
00136 return use(*pc);
00137 else
00138 return false;
00139 }
00140
00141 bool planning_environment::createConstraintRegionFromMsg(const geometric_shapes_msgs::Shape &constraint_region_shape,
00142 const geometry_msgs::Pose &constraint_region_pose,
00143 boost::scoped_ptr<bodies::Body> &body)
00144 {
00145 if(constraint_region_shape.type == geometric_shapes_msgs::Shape::SPHERE)
00146 {
00147 if(constraint_region_shape.dimensions.empty())
00148 return false;
00149 shapes::Sphere shape(constraint_region_shape.dimensions[0]);
00150 body.reset(new bodies::Sphere(&shape));
00151 }
00152 else if(constraint_region_shape.type == geometric_shapes_msgs::Shape::BOX)
00153 {
00154 if((int) constraint_region_shape.dimensions.size() < 3)
00155 return false;
00156 shapes::Box shape(constraint_region_shape.dimensions[0],constraint_region_shape.dimensions[1],constraint_region_shape.dimensions[2]);
00157 body.reset(new bodies::Box(&shape));
00158 }
00159 else if(constraint_region_shape.type == geometric_shapes_msgs::Shape::CYLINDER)
00160 {
00161 if((int) constraint_region_shape.dimensions.size() < 2)
00162 return false;
00163 shapes::Cylinder shape(constraint_region_shape.dimensions[0],constraint_region_shape.dimensions[1]);
00164 body.reset(new bodies::Cylinder(&shape));
00165 }
00166 else if(constraint_region_shape.type == geometric_shapes_msgs::Shape::MESH)
00167 {
00168 std::vector<btVector3> vertices;
00169 std::vector<unsigned int> triangles;
00170 for(unsigned int i=0; i < constraint_region_shape.triangles.size(); i++)
00171 {
00172 triangles.push_back((unsigned int) constraint_region_shape.triangles[i]);
00173 }
00174 for(unsigned int i=0; i < constraint_region_shape.triangles.size(); i++)
00175 {
00176 btVector3 tmp;
00177 tf::pointMsgToTF(constraint_region_shape.vertices[i],tmp);
00178 vertices.push_back(tmp);
00179 }
00180 shapes::Mesh *shape = shapes::createMeshFromVertices(vertices,triangles);
00181 body.reset(new bodies::ConvexMesh(shape));
00182 }
00183 else
00184 {
00185 ROS_ERROR("Could not recognize constraint type");
00186 return false;
00187 }
00188 btTransform pose_tf;
00189 tf::poseMsgToTF(constraint_region_pose,pose_tf);
00190 body->setPose(pose_tf);
00191 return true;
00192 }
00193
00194 bool planning_environment::PositionConstraintEvaluator::use(const motion_planning_msgs::PositionConstraint &pc)
00195 {
00196 m_pc = pc;
00197
00198 m_x = m_pc.position.x;
00199 m_y = m_pc.position.y;
00200 m_z = m_pc.position.z;
00201 m_offset= btVector3(m_pc.target_point_offset.x,m_pc.target_point_offset.y,m_pc.target_point_offset.z);
00202
00203 geometry_msgs::Pose constraint_region_pose;
00204 constraint_region_pose.orientation = pc.constraint_region_orientation;
00205 constraint_region_pose.position = m_pc.position;
00206 createConstraintRegionFromMsg(pc.constraint_region_shape,constraint_region_pose,m_constraint_region);
00207 ROS_DEBUG("Position Constraint: frame_id: %s",pc.header.frame_id.c_str());
00208 ROS_DEBUG("Position Constraint Desired position: (%f,%f,%f)",m_pc.position.x,m_pc.position.y,m_pc.position.z);
00209 ROS_DEBUG("Position Constraint Region: orientation: (%f,%f,%f,%f)",
00210 m_pc.constraint_region_orientation.x,
00211 m_pc.constraint_region_orientation.y,
00212 m_pc.constraint_region_orientation.z,
00213 m_pc.constraint_region_orientation.w);
00214 ROS_DEBUG("Offset (%f,%f,%f)", m_pc.target_point_offset.x,m_pc.target_point_offset.y,m_pc.target_point_offset.z);
00215 return true;
00216 }
00217
00218 bool planning_environment::OrientationConstraintEvaluator::use(const motion_planning_msgs::OrientationConstraint &oc)
00219 {
00220 m_oc = oc;
00221 btQuaternion q;
00222 tf::quaternionMsgToTF(m_oc.orientation,q);
00223 m_rotation_matrix = btMatrix3x3(q);
00224 geometry_msgs::Pose id;
00225 id.orientation.w = 1.0;
00226 ROS_DEBUG("Orientation constraint: %f %f %f %f",m_oc.orientation.x,m_oc.orientation.y,m_oc.orientation.z,m_oc.orientation.w);
00227 return true;
00228 }
00229
00230 void planning_environment::PositionConstraintEvaluator::clear(void)
00231 {
00232 }
00233
00234 void planning_environment::OrientationConstraintEvaluator::clear(void)
00235 {
00236 }
00237
00238 bool planning_environment::PositionConstraintEvaluator::decide(const planning_models::KinematicState *state,
00239 bool verbose) const
00240 {
00241 const planning_models::KinematicState::LinkState* link_state = state->getLinkState(m_pc.link_name);
00242
00243 if(!link_state)
00244 {
00245 ROS_WARN_STREAM("No link in state with name " << m_pc.link_name);
00246 return false;
00247 }
00248
00249 bool result = m_constraint_region->containsPoint(link_state->getGlobalLinkTransform()(m_offset),false);
00250 if(!result)
00251 {
00252 ROS_DEBUG("Position constraint violated : desired:: %f, %f, %f, current:: %f, %f, %f, tolerance: %f, %f, %f",m_x,m_y,m_z,
00253 link_state->getGlobalLinkTransform().getOrigin().x(),link_state->getGlobalLinkTransform().getOrigin().y(),link_state->getGlobalLinkTransform().getOrigin().z(),
00254 m_pc.constraint_region_shape.dimensions[0],m_pc.constraint_region_shape.dimensions[1],m_pc.constraint_region_shape.dimensions[2]);
00255 if(verbose) {
00256 ROS_INFO("Link name %s Position constraint satisfied: desired:: %f, %f, %f, current:: %f, %f, %f, tolerance: %f, %f, %f",link_state->getName().c_str(), m_x,m_y,m_z,
00257 link_state->getGlobalLinkTransform().getOrigin().x(),link_state->getGlobalLinkTransform().getOrigin().y(),link_state->getGlobalLinkTransform().getOrigin().z(),
00258 m_pc.constraint_region_shape.dimensions[0],m_pc.constraint_region_shape.dimensions[1],m_pc.constraint_region_shape.dimensions[2]);
00259 }
00260 }
00261 return result;
00262 }
00263
00264 bool planning_environment::OrientationConstraintEvaluator::decide(const planning_models::KinematicState *state,
00265 bool verbose) const
00266 {
00267 const planning_models::KinematicState::LinkState* link_state = state->getLinkState(m_oc.link_name);
00268
00269 if(!link_state)
00270 {
00271 ROS_WARN_STREAM("No link in state with name " << m_oc.link_name);
00272 return false;
00273 }
00274
00275
00276
00277
00278 btScalar yaw, pitch, roll;
00279 if(m_oc.type == m_oc.HEADER_FRAME)
00280 {
00281 btMatrix3x3 result = link_state->getGlobalLinkTransform().getBasis() * m_rotation_matrix.inverse();
00282 result.getRPY(roll, pitch, yaw);
00283
00284 }
00285 else
00286 {
00287 btMatrix3x3 result = m_rotation_matrix.inverse() * link_state->getGlobalLinkTransform().getBasis();
00288 result.getRPY(roll, pitch, yaw);
00289 }
00290 if(fabs(roll) < m_oc.absolute_roll_tolerance &&
00291 fabs(pitch) < m_oc.absolute_pitch_tolerance &&
00292 fabs(yaw) < m_oc.absolute_yaw_tolerance)
00293 {
00294 return true;
00295 }
00296 else
00297 {
00298 btQuaternion quat;
00299 link_state->getGlobalLinkTransform().getBasis().getRotation(quat);
00300 geometry_msgs::Quaternion quat_msg;
00301 tf::quaternionTFToMsg(quat,quat_msg);
00302 if(!verbose) {
00303 ROS_DEBUG("Orientation constraint: violated");
00304 ROS_DEBUG("Orientation Constraint: Quaternion desired: %f %f %f %f",m_oc.orientation.x,m_oc.orientation.y,m_oc.orientation.z,m_oc.orientation.w);
00305 ROS_DEBUG("Orientation Constraint: Quaternion actual: %f %f %f %f",quat_msg.x,quat_msg.y,quat_msg.z,quat_msg.w);
00306 ROS_DEBUG("Orientation Constraint: Error: Roll: %f, Pitch: %f, Yaw: %f",roll,pitch,yaw);
00307 ROS_DEBUG("Orientation Constraint: Tolerance: Roll: %f, Pitch: %f, Yaw: %f",m_oc.absolute_roll_tolerance,m_oc.absolute_pitch_tolerance,m_oc.absolute_yaw_tolerance);
00308 } else {
00309 ROS_INFO("Orientation constraint: violated");
00310 ROS_INFO("Orientation Constraint: Quaternion desired: %f %f %f %f",m_oc.orientation.x,m_oc.orientation.y,m_oc.orientation.z,m_oc.orientation.w);
00311 ROS_INFO("Orientation Constraint: Quaternion actual: %f %f %f %f",quat_msg.x,quat_msg.y,quat_msg.z,quat_msg.w);
00312 ROS_INFO("Orientation Constraint: Error: Roll: %f, Pitch: %f, Yaw: %f",roll,pitch,yaw);
00313 ROS_INFO("Orientation Constraint: Tolerance: Roll: %f, Pitch: %f, Yaw: %f",m_oc.absolute_roll_tolerance,m_oc.absolute_pitch_tolerance,m_oc.absolute_yaw_tolerance);
00314 }
00315 return false;
00316 }
00317 }
00318
00319 void planning_environment::PositionConstraintEvaluator::evaluate(const planning_models::KinematicState* state, double& distPos, bool verbose) const
00320 {
00321 const planning_models::KinematicState::LinkState* link_state = state->getLinkState(m_pc.link_name);
00322
00323 if(!link_state)
00324 {
00325 ROS_WARN_STREAM("No link in state with name " << m_pc.link_name);
00326 distPos = DBL_MAX;
00327 }
00328
00329 double dx = link_state->getGlobalLinkTransform().getOrigin().x() - m_pc.position.x;
00330 double dy = link_state->getGlobalLinkTransform().getOrigin().y() - m_pc.position.y;
00331 double dz = link_state->getGlobalLinkTransform().getOrigin().z() - m_pc.position.z;
00332
00333 distPos = sqrt(dx*dx+dy*dy+dz*dz);
00334 }
00335
00336 void planning_environment::OrientationConstraintEvaluator::evaluate(const planning_models::KinematicState* state, double& distAng, bool verbose) const
00337 {
00338 const planning_models::KinematicState::LinkState* link_state = state->getLinkState(m_oc.link_name);
00339
00340 if(!link_state)
00341 {
00342 ROS_WARN_STREAM("No link in state with name " << m_oc.link_name);
00343 distAng = DBL_MAX;
00344 }
00345
00346 distAng = 0.0;
00347 btScalar yaw, pitch, roll;
00348 if(m_oc.type == m_oc.HEADER_FRAME)
00349 {
00350 btMatrix3x3 result = m_rotation_matrix.inverse() * link_state->getGlobalLinkTransform().getBasis();
00351 result.getEulerYPR(yaw, pitch, roll);
00352 }
00353 else
00354 {
00355 btMatrix3x3 result = link_state->getGlobalLinkTransform().getBasis() * m_rotation_matrix.inverse();
00356 result.getRPY(roll, pitch, yaw);
00357 }
00358 distAng += fabs(yaw);
00359 distAng += fabs(pitch);
00360 distAng += fabs(roll);
00361 if(verbose) {
00362 std::cout << "Dist angle is " << distAng << std::endl;
00363 }
00364 }
00365
00366 bool planning_environment::PositionConstraintEvaluator::decide(double dPos, bool verbose) const
00367 {
00368 return dPos < 1e-12;
00369 }
00370
00371 bool planning_environment::OrientationConstraintEvaluator::decide(double dAng, bool verbose) const
00372 {
00373 return dAng < 1e-12;
00374 }
00375
00376 const motion_planning_msgs::PositionConstraint& planning_environment::PositionConstraintEvaluator::getConstraintMessage(void) const
00377 {
00378 return m_pc;
00379 }
00380
00381 const motion_planning_msgs::OrientationConstraint& planning_environment::OrientationConstraintEvaluator::getConstraintMessage(void) const
00382 {
00383 return m_oc;
00384 }
00385
00386 void planning_environment::PositionConstraintEvaluator::print(std::ostream &out) const
00387 {
00388 out << "Position constraint on link '" << m_pc.link_name << "'" << std::endl;
00389 if (m_pc.constraint_region_shape.type == geometric_shapes_msgs::Shape::SPHERE)
00390 {
00391 if(m_pc.constraint_region_shape.dimensions.empty())
00392 {
00393 out << "No radius specified for spherical constraint region.";
00394 }
00395 else
00396 {
00397 out << "Spherical constraint region with radius " << m_pc.constraint_region_shape.dimensions[0] << std::endl;
00398 }
00399 }
00400 else if (m_pc.constraint_region_shape.type == geometric_shapes_msgs::Shape::BOX)
00401 {
00402 if((int) m_pc.constraint_region_shape.dimensions.size() < 3)
00403 {
00404 out << "Length, width, height must be specified for box constraint region.";
00405 }
00406 else
00407 {
00408 out << "Box constraint region with dimensions " << m_pc.constraint_region_shape.dimensions[0] << " x "
00409 << m_pc.constraint_region_shape.dimensions[1] << " x " << m_pc.constraint_region_shape.dimensions[2] << std::endl;
00410 }
00411 }
00412 else if (m_pc.constraint_region_shape.type == geometric_shapes_msgs::Shape::CYLINDER)
00413 {
00414 if((int) m_pc.constraint_region_shape.dimensions.size() < 2)
00415 {
00416 out << "Radius and height must be specified for cylinder constraint region.";
00417 }
00418 else
00419 {
00420 out << "Cylinder constraint region with radius " << m_pc.constraint_region_shape.dimensions[0] << " and length "
00421 << m_pc.constraint_region_shape.dimensions[1] << std::endl;
00422 }
00423 }
00424 else if(m_pc.constraint_region_shape.type == geometric_shapes_msgs::Shape::MESH)
00425 {
00426 out << "Mesh type constraint region.";
00427 }
00428 }
00429
00430 void planning_environment::OrientationConstraintEvaluator::print(std::ostream &out) const
00431 {
00432 out << "Orientation constraint on link '" << m_oc.link_name << "'" << std::endl;
00433 out << "Desired orientation:" << m_oc.orientation.x << "," << m_oc.orientation.y << "," << m_oc.orientation.z << "," << m_oc.orientation.w << std::endl;
00434 }
00435
00436 void planning_environment::KinematicConstraintEvaluatorSet::clear(void)
00437 {
00438 for (unsigned int i = 0 ; i < m_kce.size() ; ++i)
00439 delete m_kce[i];
00440 m_kce.clear();
00441 m_jc.clear();
00442 m_pc.clear();
00443 m_oc.clear();
00444 }
00445
00446 bool planning_environment::KinematicConstraintEvaluatorSet::add(const std::vector<motion_planning_msgs::JointConstraint> &jc)
00447 {
00448 bool result = true;
00449 for (unsigned int i = 0 ; i < jc.size() ; ++i)
00450 {
00451 JointConstraintEvaluator *ev = new JointConstraintEvaluator();
00452 result = result && ev->use(jc[i]);
00453 m_kce.push_back(ev);
00454 m_jc.push_back(jc[i]);
00455 }
00456 return result;
00457 }
00458
00459 bool planning_environment::KinematicConstraintEvaluatorSet::add(const std::vector<motion_planning_msgs::PositionConstraint> &pc)
00460 {
00461 bool result = true;
00462 for (unsigned int i = 0 ; i < pc.size() ; ++i)
00463 {
00464 PositionConstraintEvaluator *ev = new PositionConstraintEvaluator();
00465 result = result && ev->use(pc[i]);
00466 m_kce.push_back(ev);
00467 m_pc.push_back(pc[i]);
00468 }
00469 return result;
00470 }
00471
00472 bool planning_environment::KinematicConstraintEvaluatorSet::add(const std::vector<motion_planning_msgs::OrientationConstraint> &oc)
00473 {
00474 bool result = true;
00475 for (unsigned int i = 0 ; i < oc.size() ; ++i)
00476 {
00477 OrientationConstraintEvaluator *ev = new OrientationConstraintEvaluator();
00478 result = result && ev->use(oc[i]);
00479 m_kce.push_back(ev);
00480 m_oc.push_back(oc[i]);
00481 }
00482 return result;
00483 }
00484
00485
00486 bool planning_environment::KinematicConstraintEvaluatorSet::add(const std::vector<motion_planning_msgs::VisibilityConstraint> &vc)
00487 {
00488 bool result = true;
00489 for (unsigned int i = 0 ; i < vc.size() ; ++i)
00490 {
00491 VisibilityConstraintEvaluator *ev = new VisibilityConstraintEvaluator();
00492 result = result && ev->use(vc[i]);
00493 m_kce.push_back(ev);
00494 m_vc.push_back(vc[i]);
00495 }
00496 return result;
00497 }
00498
00499 bool planning_environment::KinematicConstraintEvaluatorSet::decide(const planning_models::KinematicState* state,
00500 bool verbose) const
00501 {
00502 for (unsigned int i = 0 ; i < m_kce.size() ; ++i) {
00503 if (!m_kce[i]->decide(state, verbose)) {
00504 return false;
00505 }
00506 }
00507 return true;
00508 }
00509
00510 void planning_environment::KinematicConstraintEvaluatorSet::print(std::ostream &out) const
00511 {
00512 out << m_kce.size() << " kinematic constraints" << std::endl;
00513 for (unsigned int i = 0 ; i < m_kce.size() ; ++i)
00514 m_kce[i]->print(out);
00515 }
00516
00517 bool planning_environment::VisibilityConstraintEvaluator::use(const ros::Message *kc)
00518 {
00519 const motion_planning_msgs::VisibilityConstraint *pc = dynamic_cast<const motion_planning_msgs::VisibilityConstraint*>(kc);
00520 if (pc)
00521 return use(*pc);
00522 else
00523 return false;
00524 }
00525 void planning_environment::VisibilityConstraintEvaluator::print(std::ostream &out) const
00526 {
00527 out << "Visibility constraint for sensor on link '" << m_vc.sensor_pose.header.frame_id << "'" << std::endl;
00528 }
00529 const motion_planning_msgs::VisibilityConstraint& planning_environment::VisibilityConstraintEvaluator::getConstraintMessage(void) const
00530 {
00531 return m_vc;
00532 }
00533 void planning_environment::VisibilityConstraintEvaluator::clear(void)
00534 {
00535 }
00536 bool planning_environment::VisibilityConstraintEvaluator::use(const motion_planning_msgs::VisibilityConstraint &vc)
00537 {
00538 m_vc = vc;
00539 tf::poseMsgToTF(m_vc.sensor_pose.pose,m_sensor_offset_pose);
00540 return true;
00541 }
00542 bool planning_environment::VisibilityConstraintEvaluator::decide(const planning_models::KinematicState* state,
00543 bool verbose) const
00544 {
00545 std::string link_name = m_vc.sensor_pose.header.frame_id;
00546 const planning_models::KinematicState::LinkState* link_state = state->getLinkState(link_name);
00547 if(!link_state) {
00548 ROS_WARN_STREAM("No link state for link " << link_name);
00549 return false;
00550 }
00551
00552 btTransform sensor_pose = link_state->getGlobalLinkTransform() * m_sensor_offset_pose;
00553 double dx = m_vc.target.point.x - sensor_pose.getOrigin().x();
00554 double dy = m_vc.target.point.y - sensor_pose.getOrigin().y();
00555 double dz = m_vc.target.point.z - sensor_pose.getOrigin().z();
00556
00557 btVector3 x_axis(1,0,0);
00558 btVector3 target_vector(dx,dy,dz);
00559 btVector3 sensor_x_axis = sensor_pose.getBasis()*x_axis;
00560
00561 double angle = fabs(target_vector.angle(sensor_x_axis));
00562 if(angle < m_vc.absolute_tolerance)
00563 return true;
00564 else
00565 return false;
00566 }
00567