$search

flirtlib_ros Namespace Reference

Namespaces

namespace  msg
namespace  scans

Classes

struct  DescriptorRos_
struct  ExecutiveState_
struct  FlirtlibFeatures
struct  InterestPointRos_
class  MarkerNode
class  Node
struct  RefScan
struct  RefScanRos_
class  RotateInPlace
struct  RotateInPlaceAction_
struct  RotateInPlaceActionFeedback_
struct  RotateInPlaceActionGoal_
struct  RotateInPlaceActionResult_
struct  RotateInPlaceFeedback_
struct  RotateInPlaceGoal_
struct  RotateInPlaceResult_
struct  ScanMap_
class  ScanPoseEvaluator
class  ScanSimulator
struct  Vector_

Typedefs

typedef vector
< std_msgs::ColorRGBA > 
ColorVec
typedef std::pair
< InterestPoint
*, InterestPoint * > 
Correspondence
typedef vector< CorrespondenceCorrespondences
typedef
mr::MessageWithMetadata
< RefScanRos >::ConstPtr 
DBScan
typedef
::flirtlib_ros::DescriptorRos_
< std::allocator< void > > 
DescriptorRos
typedef boost::shared_ptr
< ::flirtlib_ros::DescriptorRos
const > 
DescriptorRosConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::DescriptorRos
DescriptorRosPtr
typedef
::flirtlib_ros::ExecutiveState_
< std::allocator< void > > 
ExecutiveState
typedef boost::shared_ptr
< ::flirtlib_ros::ExecutiveState
const > 
ExecutiveStateConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::ExecutiveState
ExecutiveStatePtr
typedef
::flirtlib_ros::InterestPointRos_
< std::allocator< void > > 
InterestPointRos
typedef boost::shared_ptr
< ::flirtlib_ros::InterestPointRos
const > 
InterestPointRosConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::InterestPointRos
InterestPointRosPtr
typedef std::vector
< InterestPoint * > 
InterestPointVec
typedef boost::mutex::scoped_lock Lock
typedef
mr::MessageWithMetadata
< nm::OccupancyGrid
MapWithMetadata
typedef
::flirtlib_ros::RefScanRos_
< std::allocator< void > > 
RefScanRos
typedef boost::shared_ptr
< ::flirtlib_ros::RefScanRos
const > 
RefScanRosConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RefScanRos
RefScanRosPtr
typedef vector< RefScanRefScans
typedef
::flirtlib_ros::RotateInPlaceAction_
< std::allocator< void > > 
RotateInPlaceAction
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceAction
const > 
RotateInPlaceActionConstPtr
typedef
::flirtlib_ros::RotateInPlaceActionFeedback_
< std::allocator< void > > 
RotateInPlaceActionFeedback
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceActionFeedback
const > 
RotateInPlaceActionFeedbackConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceActionFeedback
RotateInPlaceActionFeedbackPtr
typedef
::flirtlib_ros::RotateInPlaceActionGoal_
< std::allocator< void > > 
RotateInPlaceActionGoal
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceActionGoal
const > 
RotateInPlaceActionGoalConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceActionGoal
RotateInPlaceActionGoalPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceAction
RotateInPlaceActionPtr
typedef
::flirtlib_ros::RotateInPlaceActionResult_
< std::allocator< void > > 
RotateInPlaceActionResult
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceActionResult
const > 
RotateInPlaceActionResultConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceActionResult
RotateInPlaceActionResultPtr
typedef
::flirtlib_ros::RotateInPlaceFeedback_
< std::allocator< void > > 
RotateInPlaceFeedback
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceFeedback
const > 
RotateInPlaceFeedbackConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceFeedback
RotateInPlaceFeedbackPtr
typedef
::flirtlib_ros::RotateInPlaceGoal_
< std::allocator< void > > 
RotateInPlaceGoal
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceGoal
const > 
RotateInPlaceGoalConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceGoal
RotateInPlaceGoalPtr
typedef
::flirtlib_ros::RotateInPlaceResult_
< std::allocator< void > > 
RotateInPlaceResult
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceResult
const > 
RotateInPlaceResultConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::RotateInPlaceResult
RotateInPlaceResultPtr
typedef
::flirtlib_ros::ScanMap_
< std::allocator< void > > 
ScanMap
typedef boost::shared_ptr
< ::flirtlib_ros::ScanMap
const > 
ScanMapConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::ScanMap
ScanMapPtr
typedef
::flirtlib_ros::Vector_
< std::allocator< void > > 
Vector
typedef boost::shared_ptr
< ::flirtlib_ros::Vector const > 
VectorConstPtr
typedef boost::shared_ptr
< ::flirtlib_ros::Vector
VectorPtr

Functions

double angleDist (double t1, double t2)
double averageDistance (const Correspondences &corresp, const gm::Pose &p0, const gm::Pose &p1)
bool closeTo (const gm::Pose &p1, const gm::Pose &p2)
vm::Marker correspondenceMarkers (const Correspondences &correspondences, const gm::Pose &p0, const gm::Pose &p1)
DescriptorGenerator * createDescriptor (HistogramDistance< double > *dist)
Detector * createDetector (SimpleMinMaxPeakFinder *peak_finder)
SimpleMinMaxPeakFinder * createPeakFinder ()
ros::Duration duration (const double r)
Descriptor * fromRos (const DescriptorRos &m)
vector< vector< double > > fromRos (const vector< Vector > &m)
std::vector< RefScanfromRos (const ScanMap &scan_map)
 Convert a ScanMap to a set of ref scans.
RefScan fromRos (const RefScanRos &r)
 Convert a single RefScanRos message to a RefScan.
InterestPoint * fromRos (const InterestPointRos &m)
boost::shared_ptr< LaserReading > fromRos (const sensor_msgs::LaserScan &scan)
 Convert a ROS laser scan message to a flirtlib scan.
gm::Pose getCurrentPose (const tf::TransformListener &tf, const std::string &frame)
tf::Transform getLaserOffset (const tf::TransformListener &tf)
 Get transform from base_footprint and base_laser_link.
template<typename T >
getParam (const string &name, const T &default_val)
template<class T >
getPrivateParam (const string &name, const T &default_val)
template<class T >
getPrivateParam (const string &name)
template<typename T >
getPrivateParam (const std::string &name, const T &default_val)
sm::LaserScan getScannerParams ()
unsigned getSum (const nm::OccupancyGrid &g)
 This is sort of like a hash for the map.
ColorVec initColors ()
visualization_msgs::Marker interestPointMarkers (const std::vector< InterestPoint * > &pts, const geometry_msgs::Pose &pose, unsigned id=0)
tf::Transform loadLaserOffset ()
gm::Pose makePose (double x, double y, double theta)
 Create a 2d pose.
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::Vector_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::ScanMap_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceResult_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceGoal_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceFeedback_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceActionResult_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceActionGoal_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceActionFeedback_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RotateInPlaceAction_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::RefScanRos_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::InterestPointRos_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::ExecutiveState_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::flirtlib_ros::DescriptorRos_< ContainerAllocator > &v)
vector< vm::MarkerposeMarkers (const vector< gm::Pose > &poses)
std::vector
< visualization_msgs::Marker
poseMarkers (const std::vector< geometry_msgs::Pose > &poses)
 Markers for a set of poses.
tf::Pose poseMsgToTf (const gm::Pose &p)
 Convert geometry_msgs::Pose to tf.
gm::Pose tfTransformToPose (const tf::Transform &trans)
 Convert tf transform to ros pose.
gm::Point toPoint (const Point2D &p)
gm::Point toPoint (const tf::Vector3 &p)
Point2D toPoint2D (const gm::Point &p)
ScanMap toRos (const vector< RefScan > &scans)
DescriptorRos toRos (const Descriptor *descriptor)
vector< VectortoRos (const vector< vector< double > > &h)
ScanMap toRos (const std::vector< RefScan > &scans)
 Convert a vector of RefScan's to a ScanMap.
RefScanRos toRos (const RefScan &r)
 Convert a single RefScan to a ROS message.
InterestPointRos toRos (const InterestPoint &pt)
 Convert a flirtlib interest point to InterestPointRos.
tf::StampedTransform toTf (const gm::Pose &p, const string &frame)
gm::Pose transformPose (const tf::Transform &trans, const gm::Pose &pose)
 Transform a pose using a tf transform.
gm::Pose transformPose (const gm::Pose &p, const OrientedPoint2D &trans)
 Transform a flirtlib 2d pose.

Typedef Documentation

typedef vector<std_msgs::ColorRGBA> flirtlib_ros::ColorVec

Definition at line 74 of file conversions.cpp.

typedef std::pair< InterestPoint *, InterestPoint * > flirtlib_ros::Correspondence

Definition at line 102 of file localization_monitor_node.cpp.

Definition at line 103 of file localization_monitor_node.cpp.

Definition at line 101 of file localization_monitor_node.cpp.

Definition at line 141 of file DescriptorRos.h.

Definition at line 144 of file DescriptorRos.h.

Definition at line 143 of file DescriptorRos.h.

Definition at line 108 of file ExecutiveState.h.

Definition at line 111 of file ExecutiveState.h.

Definition at line 110 of file ExecutiveState.h.

Definition at line 166 of file InterestPointRos.h.

Definition at line 169 of file InterestPointRos.h.

Definition at line 168 of file InterestPointRos.h.

typedef vector< InterestPoint * > flirtlib_ros::InterestPointVec

Definition at line 65 of file flirtlib.h.

typedef boost::mutex::scoped_lock flirtlib_ros::Lock

Definition at line 57 of file generate_scan_map.cpp.

Definition at line 105 of file localization_monitor_node.cpp.

typedef ::flirtlib_ros::RefScanRos_<std::allocator<void> > flirtlib_ros::RefScanRos

Definition at line 220 of file RefScanRos.h.

typedef boost::shared_ptr< ::flirtlib_ros::RefScanRos const> flirtlib_ros::RefScanRosConstPtr

Definition at line 223 of file RefScanRos.h.

Definition at line 222 of file RefScanRos.h.

typedef vector< RefScan > flirtlib_ros::RefScans

Definition at line 104 of file localization_monitor_node.cpp.

Definition at line 209 of file RotateInPlaceAction.h.

Definition at line 212 of file RotateInPlaceAction.h.

Definition at line 171 of file RotateInPlaceActionFeedback.h.

Definition at line 174 of file RotateInPlaceActionFeedback.h.

Definition at line 173 of file RotateInPlaceActionFeedback.h.

Definition at line 148 of file RotateInPlaceActionGoal.h.

Definition at line 151 of file RotateInPlaceActionGoal.h.

Definition at line 150 of file RotateInPlaceActionGoal.h.

Definition at line 211 of file RotateInPlaceAction.h.

Definition at line 172 of file RotateInPlaceActionResult.h.

Definition at line 175 of file RotateInPlaceActionResult.h.

Definition at line 174 of file RotateInPlaceActionResult.h.

Definition at line 79 of file RotateInPlaceFeedback.h.

Definition at line 82 of file RotateInPlaceFeedback.h.

Definition at line 81 of file RotateInPlaceFeedback.h.

Definition at line 125 of file RotateInPlaceGoal.h.

Definition at line 128 of file RotateInPlaceGoal.h.

Definition at line 127 of file RotateInPlaceGoal.h.

Definition at line 88 of file RotateInPlaceResult.h.

Definition at line 91 of file RotateInPlaceResult.h.

Definition at line 90 of file RotateInPlaceResult.h.

typedef ::flirtlib_ros::ScanMap_<std::allocator<void> > flirtlib_ros::ScanMap

Definition at line 205 of file ScanMap.h.

typedef boost::shared_ptr< ::flirtlib_ros::ScanMap const> flirtlib_ros::ScanMapConstPtr

Definition at line 208 of file ScanMap.h.

typedef boost::shared_ptr< ::flirtlib_ros::ScanMap> flirtlib_ros::ScanMapPtr

Definition at line 207 of file ScanMap.h.

typedef ::flirtlib_ros::Vector_<std::allocator<void> > flirtlib_ros::Vector

Definition at line 91 of file Vector.h.

typedef boost::shared_ptr< ::flirtlib_ros::Vector const> flirtlib_ros::VectorConstPtr

Definition at line 94 of file Vector.h.

typedef boost::shared_ptr< ::flirtlib_ros::Vector> flirtlib_ros::VectorPtr

Definition at line 93 of file Vector.h.


Function Documentation

double flirtlib_ros::angleDist ( double  t1,
double  t2 
) [inline]

Definition at line 125 of file generate_scan_map.cpp.

double flirtlib_ros::averageDistance ( const Correspondences corresp,
const gm::Pose p0,
const gm::Pose p1 
)

Definition at line 78 of file flirtlib_ros_test.cpp.

bool flirtlib_ros::closeTo ( const gm::Pose p1,
const gm::Pose p2 
)

Definition at line 336 of file place_rec_test.cpp.

vm::Marker flirtlib_ros::correspondenceMarkers ( const Correspondences correspondences,
const gm::Pose p0,
const gm::Pose p1 
)

Definition at line 198 of file flirtlib_ros_test.cpp.

DescriptorGenerator * flirtlib_ros::createDescriptor ( HistogramDistance< double > *  dist  ) 

Definition at line 160 of file startup_loc.cpp.

Detector * flirtlib_ros::createDetector ( SimpleMinMaxPeakFinder *  peak_finder  ) 

Definition at line 148 of file startup_loc.cpp.

SimpleMinMaxPeakFinder * flirtlib_ros::createPeakFinder (  ) 

Definition at line 143 of file startup_loc.cpp.

ros::Duration flirtlib_ros::duration ( const double  r  ) 

Definition at line 103 of file interactive_markers.cpp.

Descriptor* flirtlib_ros::fromRos ( const DescriptorRos &  m  ) 

Definition at line 237 of file conversions.cpp.

vector<vector<double> > flirtlib_ros::fromRos ( const vector< Vector > &  m  ) 

Definition at line 213 of file conversions.cpp.

vector< RefScan > flirtlib_ros::fromRos ( const ScanMap &  scan_map  ) 

Convert a ScanMap to a set of ref scans.

Definition at line 301 of file conversions.cpp.

RefScan flirtlib_ros::fromRos ( const RefScanRos &  r  ) 

Convert a single RefScanRos message to a RefScan.

Definition at line 281 of file conversions.cpp.

InterestPoint * flirtlib_ros::fromRos ( const InterestPointRos &  m  ) 

Convert a ROS interest point to flirtlib The caller owns the resulting pointer

Definition at line 268 of file conversions.cpp.

LaserPtr flirtlib_ros::fromRos ( const sensor_msgs::LaserScan scan  ) 

Convert a ROS laser scan message to a flirtlib scan.

Definition at line 57 of file conversions.cpp.

gm::Pose flirtlib_ros::getCurrentPose ( const tf::TransformListener tf,
const std::string &  frame 
)

Get the current pose of the laser link in the map frame

Exceptions:
Tf exceptions

Definition at line 44 of file common.cpp.

tf::Transform flirtlib_ros::getLaserOffset ( const tf::TransformListener tf  ) 

Get transform from base_footprint and base_laser_link.

Definition at line 85 of file common.cpp.

template<typename T >
T flirtlib_ros::getParam ( const string &  name,
const T &  default_val 
) [inline]

Definition at line 94 of file interactive_markers.cpp.

template<class T >
T flirtlib_ros::getPrivateParam ( const string &  name,
const T &  default_val 
) [inline]

Definition at line 133 of file startup_loc.cpp.

template<class T >
T flirtlib_ros::getPrivateParam ( const string &  name  )  [inline]

Definition at line 122 of file startup_loc.cpp.

template<typename T >
T flirtlib_ros::getPrivateParam ( const std::string &  name,
const T &  default_val 
) [inline]

Load a private parameter Requires ros::init to have been called. Also, make sure an external node handle is in scope before calling this.

Definition at line 74 of file common.h.

sm::LaserScan flirtlib_ros::getScannerParams (  ) 

Definition at line 92 of file simulate_scans.cpp.

unsigned flirtlib_ros::getSum ( const nm::OccupancyGrid g  ) 

This is sort of like a hash for the map.

Definition at line 318 of file localization_monitor_node.cpp.

ColorVec flirtlib_ros::initColors (  ) 

Definition at line 75 of file conversions.cpp.

vm::Marker flirtlib_ros::interestPointMarkers ( const std::vector< InterestPoint * > &  pts,
const geometry_msgs::Pose pose,
unsigned  id = 0 
)

Turn a set of interest points into visualization markers. id can be 0 or 1 to control color and orientation when distinguishing two scans.

Definition at line 135 of file conversions.cpp.

tf::Transform flirtlib_ros::loadLaserOffset (  ) 

Definition at line 172 of file startup_loc.cpp.

gm::Pose flirtlib_ros::makePose ( double  x,
double  y,
double  theta 
)

Create a 2d pose.

Definition at line 205 of file startup_loc.cpp.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::Vector_< ContainerAllocator > &  v 
) [inline]

Definition at line 98 of file Vector.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::ScanMap_< ContainerAllocator > &  v 
) [inline]

Definition at line 212 of file ScanMap.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceResult_< ContainerAllocator > &  v 
) [inline]

Definition at line 95 of file RotateInPlaceResult.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceGoal_< ContainerAllocator > &  v 
) [inline]

Definition at line 132 of file RotateInPlaceGoal.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceFeedback_< ContainerAllocator > &  v 
) [inline]

Definition at line 86 of file RotateInPlaceFeedback.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceActionResult_< ContainerAllocator > &  v 
) [inline]

Definition at line 179 of file RotateInPlaceActionResult.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceActionGoal_< ContainerAllocator > &  v 
) [inline]

Definition at line 155 of file RotateInPlaceActionGoal.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceActionFeedback_< ContainerAllocator > &  v 
) [inline]

Definition at line 178 of file RotateInPlaceActionFeedback.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RotateInPlaceAction_< ContainerAllocator > &  v 
) [inline]

Definition at line 216 of file RotateInPlaceAction.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::RefScanRos_< ContainerAllocator > &  v 
) [inline]

Definition at line 227 of file RefScanRos.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::InterestPointRos_< ContainerAllocator > &  v 
) [inline]

Definition at line 173 of file InterestPointRos.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::ExecutiveState_< ContainerAllocator > &  v 
) [inline]

Definition at line 115 of file ExecutiveState.h.

template<typename ContainerAllocator >
std::ostream& flirtlib_ros::operator<< ( std::ostream &  s,
const ::flirtlib_ros::DescriptorRos_< ContainerAllocator > &  v 
) [inline]

Definition at line 148 of file DescriptorRos.h.

vector<vm::Marker> flirtlib_ros::poseMarkers ( const vector< gm::Pose > &  poses  ) 

Definition at line 89 of file conversions.cpp.

std::vector<visualization_msgs::Marker> flirtlib_ros::poseMarkers ( const std::vector< geometry_msgs::Pose > &  poses  ) 

Markers for a set of poses.

tf::Pose flirtlib_ros::poseMsgToTf ( const gm::Pose p  )  [inline]

Convert geometry_msgs::Pose to tf.

Definition at line 61 of file common.h.

gm::Pose flirtlib_ros::tfTransformToPose ( const tf::Transform trans  )  [inline]

Convert tf transform to ros pose.

Definition at line 52 of file common.h.

gm::Point flirtlib_ros::toPoint ( const Point2D &  p  )  [inline]

Definition at line 185 of file conversions.cpp.

gm::Point flirtlib_ros::toPoint ( const tf::Vector3 p  ) 

Definition at line 69 of file flirtlib_ros_test.cpp.

Point2D flirtlib_ros::toPoint2D ( const gm::Point p  )  [inline]

Definition at line 194 of file conversions.cpp.

ScanMap flirtlib_ros::toRos ( const vector< RefScan > &  scans  ) 

Definition at line 309 of file conversions.cpp.

DescriptorRos flirtlib_ros::toRos ( const Descriptor *  descriptor  ) 

Definition at line 222 of file conversions.cpp.

vector<Vector> flirtlib_ros::toRos ( const vector< vector< double > > &  h  ) 

Definition at line 199 of file conversions.cpp.

ScanMap flirtlib_ros::toRos ( const std::vector< RefScan > &  scans  ) 

Convert a vector of RefScan's to a ScanMap.

RefScanRos flirtlib_ros::toRos ( const RefScan &  r  ) 

Convert a single RefScan to a ROS message.

Definition at line 290 of file conversions.cpp.

InterestPointRos flirtlib_ros::toRos ( const InterestPoint &  pt  ) 

Convert a flirtlib interest point to InterestPointRos.

Definition at line 248 of file conversions.cpp.

tf::StampedTransform flirtlib_ros::toTf ( const gm::Pose p,
const string &  frame 
)

Definition at line 160 of file interactive_markers.cpp.

gm::Pose flirtlib_ros::transformPose ( const tf::Transform trans,
const gm::Pose pose 
)

Transform a pose using a tf transform.

Definition at line 259 of file startup_loc.cpp.

gm::Pose flirtlib_ros::transformPose ( const gm::Pose p,
const OrientedPoint2D &  trans 
)

Transform a flirtlib 2d pose.

Definition at line 247 of file startup_loc.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


flirtlib_ros
Author(s): Bhaskara Marthi
autogenerated on Fri Mar 1 15:36:22 2013