planning_environment::OrientationConstraintEvaluator Class Reference

#include <kinematic_state_constraint_evaluator.h>

Inheritance diagram for planning_environment::OrientationConstraintEvaluator:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void clear (void)
 Clear the stored constraint.
bool decide (double dAng, bool verbose=false) const
 Decide whether the constraint is satisfied. The distances to the position and to the orientation are given.
virtual bool decide (const planning_models::KinematicState *state, bool verbose=false) const
 Decide whether the constraint is satisfied in the indicated state or group, if specified.
void evaluate (const planning_models::KinematicState *state, double &distAng, bool verbose=false) const
 Evaluate the distances to the position and to the orientation are given.
const
motion_planning_msgs::OrientationConstraint & 
getConstraintMessage (void) const
 Get the constraint message.
 OrientationConstraintEvaluator (void)
void print (std::ostream &out=std::cout) const
 Print the constraint data.
bool use (const motion_planning_msgs::OrientationConstraint &pc)
 This function assumes the constraint has been transformed into the proper frame, if such a transform is needed.
virtual bool use (const ros::Message *kc)
 This function assumes the constraint has been transformed into the proper frame, if such a transform is needed.

Protected Attributes

boost::scoped_ptr< bodies::Body > m_constraint_region
motion_planning_msgs::OrientationConstraint m_oc
double m_pitch
double m_roll
btMatrix3x3 m_rotation_matrix
double m_yaw

Detailed Description

Definition at line 120 of file kinematic_state_constraint_evaluator.h.


Constructor & Destructor Documentation

planning_environment::OrientationConstraintEvaluator::OrientationConstraintEvaluator ( void   )  [inline]

Definition at line 124 of file kinematic_state_constraint_evaluator.h.


Member Function Documentation

void planning_environment::OrientationConstraintEvaluator::clear ( void   )  [virtual]

Clear the stored constraint.

Implements planning_environment::KinematicConstraintEvaluator.

Definition at line 234 of file kinematic_state_constraint_evaluator.cpp.

bool planning_environment::OrientationConstraintEvaluator::decide ( double  dAng,
bool  verbose = false 
) const

Decide whether the constraint is satisfied. The distances to the position and to the orientation are given.

Definition at line 371 of file kinematic_state_constraint_evaluator.cpp.

bool planning_environment::OrientationConstraintEvaluator::decide ( const planning_models::KinematicState *  state,
bool  verbose = false 
) const [virtual]

Decide whether the constraint is satisfied in the indicated state or group, if specified.

Implements planning_environment::KinematicConstraintEvaluator.

Definition at line 264 of file kinematic_state_constraint_evaluator.cpp.

void planning_environment::OrientationConstraintEvaluator::evaluate ( const planning_models::KinematicState *  state,
double &  distAng,
bool  verbose = false 
) const

Evaluate the distances to the position and to the orientation are given.

Definition at line 336 of file kinematic_state_constraint_evaluator.cpp.

const motion_planning_msgs::OrientationConstraint & planning_environment::OrientationConstraintEvaluator::getConstraintMessage ( void   )  const

Get the constraint message.

Definition at line 381 of file kinematic_state_constraint_evaluator.cpp.

void planning_environment::OrientationConstraintEvaluator::print ( std::ostream &  out = std::cout  )  const [virtual]

Print the constraint data.

Reimplemented from planning_environment::KinematicConstraintEvaluator.

Definition at line 430 of file kinematic_state_constraint_evaluator.cpp.

bool planning_environment::OrientationConstraintEvaluator::use ( const motion_planning_msgs::OrientationConstraint &  pc  ) 

This function assumes the constraint has been transformed into the proper frame, if such a transform is needed.

Definition at line 218 of file kinematic_state_constraint_evaluator.cpp.

bool planning_environment::OrientationConstraintEvaluator::use ( const ros::Message *  kc  )  [virtual]

This function assumes the constraint has been transformed into the proper frame, if such a transform is needed.

Implements planning_environment::KinematicConstraintEvaluator.

Definition at line 132 of file kinematic_state_constraint_evaluator.cpp.


Member Data Documentation

Definition at line 158 of file kinematic_state_constraint_evaluator.h.

motion_planning_msgs::OrientationConstraint planning_environment::OrientationConstraintEvaluator::m_oc [protected]

Definition at line 155 of file kinematic_state_constraint_evaluator.h.

Definition at line 156 of file kinematic_state_constraint_evaluator.h.

Definition at line 156 of file kinematic_state_constraint_evaluator.h.

Definition at line 157 of file kinematic_state_constraint_evaluator.h.

Definition at line 156 of file kinematic_state_constraint_evaluator.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Enumerator Friends


planning_environment
Author(s): Ioan Sucan
autogenerated on Fri Jan 11 10:03:07 2013