$search

FindBasePoseAction Class Reference

end: exlude unknown and occupied space from map More...

List of all members.

Public Member Functions

bool collisionFree (btTransform relativePose)
bool collisionFreeCoarse (btTransform relativePose)
bool collisionFreeFine (btTransform relativePose)
void executeCB (const find_base_pose::FindBasePoseGoalConstPtr &goal)
 FindBasePoseAction (std::string name)
void generateCandidatePoses (std::vector< tf::Pose > &search_poses, std::vector< tf::Stamped< tf::Pose > > target_poses, tf::Pose preTrans, const std::vector< std_msgs::Int32 > &arm)
tf::Stamped< tf::PosegetPoseIn (const char target_frame[], tf::Stamped< tf::Pose >src)
bool insideBB (int side, geometry_msgs::PoseStamped pose)
void pubBaseMarker (std::vector< btVector3 > pts, float colr=0, float colg=1, float colb=0, float si_=0.325)
void pubBaseMarker (tf::Pose pose, float colr=0, float colg=1, float colb=0, float si_=0.325)
void pubBaseMarker (float dx, float dy, float dz=0, float colr=0, float colg=1, float colb=0, float si_=0.325)
void pubBaseMarkerArrow (geometry_msgs::PoseStamped pose, float colr=0, float colg=1, float colb=0)
void pubBaseMarkerArrow (tf::Pose pose, float colr=0, float colg=1, float colb=0)
void pubBaseMarkerBlob (tf::Pose pose, float colr=0, float colg=1, float colb=0)
void pubBaseMarkerBlob (float dx, float dy, float dz, float colr=0, float colg=1, float colb=0)
tf::Pose rotateAroundPose (tf::Pose toolPose, tf::Pose pivot, btQuaternion qa)
bool run_ik (int side_, geometry_msgs::PoseStamped pose, double start_angles[7], double solution[7])
void scanCallback (const sensor_msgs::LaserScan::ConstPtr &scan_in)
tf::Stamped< tf::Posetool2wrist (tf::Stamped< tf::Pose > toolPose)
 ~FindBasePoseAction (void)

Static Public Member Functions

static bool pose_compare (tf::Pose a, tf::Pose b)

Protected Attributes

std::string action_name_
actionlib::SimpleActionServer
< find_base_pose::FindBasePoseAction
as_
btVector3 bbox [2][2]
find_base_pose::FindBasePoseFeedback feedback_
ros::ServiceClient ik_client [2]
tf::TransformListenerlistener_
int markerCnt
ros::NodeHandle nh_
size_t numScanPoints
laser_geometry::LaserProjectionprojector_
find_base_pose::FindBasePoseResult result_
boost::mutex scan_mutex
btVector3 scanPoints [5000]
ros::Subscriber subScan_
 We need laser scans for avoiding obstacles.
ros::Publisher vis_pub
bool weHaveScan

Detailed Description

end: exlude unknown and occupied space from map

Definition at line 245 of file find_base_pose.cpp.


Constructor & Destructor Documentation

FindBasePoseAction::FindBasePoseAction ( std::string  name  )  [inline]

Definition at line 277 of file find_base_pose.cpp.

FindBasePoseAction::~FindBasePoseAction ( void   )  [inline]

Definition at line 313 of file find_base_pose.cpp.


Member Function Documentation

bool FindBasePoseAction::collisionFree ( btTransform  relativePose  )  [inline]

Definition at line 689 of file find_base_pose.cpp.

bool FindBasePoseAction::collisionFreeCoarse ( btTransform  relativePose  )  [inline]

Definition at line 644 of file find_base_pose.cpp.

bool FindBasePoseAction::collisionFreeFine ( btTransform  relativePose  )  [inline]

Definition at line 660 of file find_base_pose.cpp.

void FindBasePoseAction::executeCB ( const find_base_pose::FindBasePoseGoalConstPtr goal  )  [inline]

Definition at line 1059 of file find_base_pose.cpp.

void FindBasePoseAction::generateCandidatePoses ( std::vector< tf::Pose > &  search_poses,
std::vector< tf::Stamped< tf::Pose > >  target_poses,
tf::Pose  preTrans,
const std::vector< std_msgs::Int32 > &  arm 
) [inline]

Definition at line 961 of file find_base_pose.cpp.

tf::Stamped<tf::Pose> FindBasePoseAction::getPoseIn ( const char  target_frame[],
tf::Stamped< tf::Pose src 
) [inline]

Definition at line 751 of file find_base_pose.cpp.

bool FindBasePoseAction::insideBB ( int  side,
geometry_msgs::PoseStamped  pose 
) [inline]

Definition at line 784 of file find_base_pose.cpp.

static bool FindBasePoseAction::pose_compare ( tf::Pose  a,
tf::Pose  b 
) [inline, static]

Definition at line 954 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarker ( std::vector< btVector3 >  pts,
float  colr = 0,
float  colg = 1,
float  colb = 0,
float  si_ = 0.325 
) [inline]

Definition at line 574 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarker ( tf::Pose  pose,
float  colr = 0,
float  colg = 1,
float  colb = 0,
float  si_ = 0.325 
) [inline]

Definition at line 496 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarker ( float  dx,
float  dy,
float  dz = 0,
float  colr = 0,
float  colg = 1,
float  colb = 0,
float  si_ = 0.325 
) [inline]

Definition at line 425 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarkerArrow ( geometry_msgs::PoseStamped  pose,
float  colr = 0,
float  colg = 1,
float  colb = 0 
) [inline]

Definition at line 398 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarkerArrow ( tf::Pose  pose,
float  colr = 0,
float  colg = 1,
float  colb = 0 
) [inline]

Definition at line 371 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarkerBlob ( tf::Pose  pose,
float  colr = 0,
float  colg = 1,
float  colb = 0 
) [inline]

Definition at line 344 of file find_base_pose.cpp.

void FindBasePoseAction::pubBaseMarkerBlob ( float  dx,
float  dy,
float  dz,
float  colr = 0,
float  colg = 1,
float  colb = 0 
) [inline]

Definition at line 317 of file find_base_pose.cpp.

tf::Pose FindBasePoseAction::rotateAroundPose ( tf::Pose  toolPose,
tf::Pose  pivot,
btQuaternion  qa 
) [inline]

Definition at line 798 of file find_base_pose.cpp.

bool FindBasePoseAction::run_ik ( int  side_,
geometry_msgs::PoseStamped  pose,
double  start_angles[7],
double  solution[7] 
) [inline]

TODO: generally we should be able to interface ik on a lower level

Definition at line 821 of file find_base_pose.cpp.

void FindBasePoseAction::scanCallback ( const sensor_msgs::LaserScan::ConstPtr scan_in  )  [inline]

Definition at line 619 of file find_base_pose.cpp.

tf::Stamped<tf::Pose> FindBasePoseAction::tool2wrist ( tf::Stamped< tf::Pose toolPose  )  [inline]

Definition at line 739 of file find_base_pose.cpp.


Member Data Documentation

std::string FindBasePoseAction::action_name_ [protected]

Definition at line 251 of file find_base_pose.cpp.

Definition at line 250 of file find_base_pose.cpp.

btVector3 FindBasePoseAction::bbox[2][2] [protected]

Definition at line 269 of file find_base_pose.cpp.

Definition at line 253 of file find_base_pose.cpp.

Definition at line 256 of file find_base_pose.cpp.

Definition at line 255 of file find_base_pose.cpp.

Definition at line 273 of file find_base_pose.cpp.

Definition at line 249 of file find_base_pose.cpp.

Definition at line 266 of file find_base_pose.cpp.

Definition at line 260 of file find_base_pose.cpp.

Definition at line 254 of file find_base_pose.cpp.

boost::mutex FindBasePoseAction::scan_mutex [protected]

Definition at line 261 of file find_base_pose.cpp.

btVector3 FindBasePoseAction::scanPoints[5000] [protected]

Definition at line 264 of file find_base_pose.cpp.

We need laser scans for avoiding obstacles.

Definition at line 259 of file find_base_pose.cpp.

Definition at line 271 of file find_base_pose.cpp.

Definition at line 262 of file find_base_pose.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


find_base_pose
Author(s): Thomas Ruehr
autogenerated on Tue Dec 4 06:03:41 2012