#include <psm_node.h>
Public Member Functions | |
PSMNode () | |
virtual | ~PSMNode () |
Private Member Functions | |
void | getCurrentEstimatedPose (tf::Transform &worldToBase, const sensor_msgs::LaserScan &scanMsg) |
void | getParams () |
void | imuCallback (const sensor_msgs::Imu &imuMsg) |
bool | initialize (const sensor_msgs::LaserScan &scan) |
void | pose2DToTf (const geometry_msgs::Pose2D &pose, tf::Transform &t) |
void | publishPose (const tf::Transform &transform) |
void | publishTf (const tf::Transform &transform, const ros::Time &time) |
void | rosToPMScan (const sensor_msgs::LaserScan &scan, const tf::Transform &change, PMScan *pmScan) |
void | scanCallback (const sensor_msgs::LaserScan &scan) |
void | tfToPose2D (const tf::Transform &t, geometry_msgs::Pose2D &pose) |
Private Attributes | |
std::string | baseFrame_ |
tf::Transform | baseToLaser_ |
double | currImuAngle_ |
boost::mutex | imuMutex_ |
ros::Subscriber | imuSubscriber_ |
bool | initialized_ |
std::string | laserFrame_ |
tf::Transform | laserToBase_ |
PolarMatcher | matcher_ |
double | maxError_ |
int | maxIterations_ |
int | minValidPoints_ |
ros::Publisher | posePublisher_ |
double | prevImuAngle_ |
PMScan * | prevPMScan_ |
tf::Transform | prevWorldToBase_ |
bool | publishPose_ |
bool | publishTf_ |
int | scansCount_ |
ros::Subscriber | scanSubscriber_ |
int | searchWindow_ |
double | stopCondition_ |
tf::TransformBroadcaster | tfBroadcaster_ |
tf::TransformListener | tfListener_ |
double | totalDuration_ |
bool | useImuOdometry_ |
bool | useTfOdometry_ |
std::string | worldFrame_ |
Definition at line 51 of file psm_node.h.
PSMNode::PSMNode | ( | ) |
Definition at line 40 of file psm_node.cpp.
|
virtual |
Definition at line 59 of file psm_node.cpp.
|
private |
Definition at line 339 of file psm_node.cpp.
|
private |
Definition at line 64 of file psm_node.cpp.
|
private |
Definition at line 174 of file psm_node.cpp.
|
private |
Definition at line 120 of file psm_node.cpp.
|
private |
Definition at line 357 of file psm_node.cpp.
|
private |
Definition at line 296 of file psm_node.cpp.
|
private |
Definition at line 289 of file psm_node.cpp.
|
private |
Definition at line 304 of file psm_node.cpp.
|
private |
Definition at line 184 of file psm_node.cpp.
|
private |
Definition at line 365 of file psm_node.cpp.
|
private |
Definition at line 90 of file psm_node.h.
|
private |
Definition at line 62 of file psm_node.h.
|
private |
Definition at line 74 of file psm_node.h.
|
private |
Definition at line 72 of file psm_node.h.
|
private |
Definition at line 56 of file psm_node.h.
|
private |
Definition at line 65 of file psm_node.h.
|
private |
Definition at line 91 of file psm_node.h.
|
private |
Definition at line 63 of file psm_node.h.
|
private |
Definition at line 69 of file psm_node.h.
|
private |
Definition at line 85 of file psm_node.h.
|
private |
Definition at line 86 of file psm_node.h.
|
private |
Definition at line 83 of file psm_node.h.
|
private |
Definition at line 57 of file psm_node.h.
|
private |
Definition at line 73 of file psm_node.h.
|
private |
Definition at line 70 of file psm_node.h.
|
private |
Definition at line 61 of file psm_node.h.
|
private |
Definition at line 79 of file psm_node.h.
|
private |
Definition at line 78 of file psm_node.h.
|
private |
Definition at line 67 of file psm_node.h.
|
private |
Definition at line 55 of file psm_node.h.
|
private |
Definition at line 84 of file psm_node.h.
|
private |
Definition at line 87 of file psm_node.h.
|
private |
Definition at line 59 of file psm_node.h.
|
private |
Definition at line 60 of file psm_node.h.
|
private |
Definition at line 66 of file psm_node.h.
|
private |
Definition at line 81 of file psm_node.h.
|
private |
Definition at line 80 of file psm_node.h.
|
private |
Definition at line 89 of file psm_node.h.