Skip to content

Commit af22250

Browse files
authored
Merge pull request #79 from malban/refactor-prediction-and-transforms
Refactor and correct prediction code and transforms.
2 parents 06af357 + 4ad6c92 commit af22250

2 files changed

Lines changed: 108 additions & 91 deletions

File tree

laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher.h

Lines changed: 20 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -88,8 +88,8 @@ class LaserScanMatcher
8888
tf::TransformListener tf_listener_;
8989
tf::TransformBroadcaster tf_broadcaster_;
9090

91-
tf::Transform base_to_laser_; // static, cached
92-
tf::Transform laser_to_base_; // static, cached, calculated from base_to_laser_
91+
tf::Transform base_from_laser_; // static, cached
92+
tf::Transform laser_from_base_; // static, cached
9393

9494
ros::Publisher pose_publisher_;
9595
ros::Publisher pose_stamped_publisher_;
@@ -120,11 +120,14 @@ class LaserScanMatcher
120120
// **** What predictions are available to speed up the ICP?
121121
// 1) imu - [theta] from imu yaw angle - /imu topic
122122
// 2) odom - [x, y, theta] from wheel odometry - /odom topic
123+
// 3) tf - [x, y, theta] from /tf topic
123124
// 3) velocity [vx, vy, vtheta], usually from ab-filter - /vel.
124-
// If more than one is enabled, priority is imu > odom > velocity
125+
// If more than one is enabled, priority is tf > imu > odom > velocity
125126

126127
bool use_imu_;
127128
bool use_odom_;
129+
bool use_tf_;
130+
double tf_timeout_;
128131
bool use_vel_;
129132
bool stamped_vel_;
130133

@@ -137,15 +140,15 @@ class LaserScanMatcher
137140
bool received_odom_;
138141
bool received_vel_;
139142

140-
tf::Transform f2b_; // fixed-to-base tf (pose of base frame in fixed frame)
141-
tf::Transform f2b_kf_; // pose of the last keyframe scan in fixed frame
143+
tf::Transform last_base_in_fixed_; // pose of the base of the last scan in fixed frame
144+
tf::Transform keyframe_base_in_fixed_; // pose of the base of last keyframe scan in fixed frame
142145

143146
ros::Time last_icp_time_;
144147

145148
sensor_msgs::Imu latest_imu_msg_;
146-
sensor_msgs::Imu last_used_imu_msg_;
149+
tf::Quaternion last_used_imu_orientation_;
147150
nav_msgs::Odometry latest_odom_msg_;
148-
nav_msgs::Odometry last_used_odom_msg_;
151+
tf::Transform last_used_odom_pose_;
149152

150153
geometry_msgs::Twist latest_vel_msg_;
151154

@@ -175,12 +178,19 @@ class LaserScanMatcher
175178
void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg);
176179

177180
void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
178-
bool getBaseToLaserTf (const std::string& frame_id);
181+
182+
/**
183+
* Cache the static transform between the base and laser.
184+
*
185+
* @param[in] frame_id The laser frame.
186+
*
187+
* @returns True if the transform was found, false otherwise.
188+
*/
189+
bool getBaseLaserTransform(const std::string& frame_id);
179190

180191
bool newKeyframeNeeded(const tf::Transform& d);
181192

182-
void getPrediction(double& pr_ch_x, double& pr_ch_y,
183-
double& pr_ch_a, double dt);
193+
tf::Transform getPrediction(const ros::Time& stamp);
184194

185195
void createTfFromXYTheta(double x, double y, double theta, tf::Transform& t);
186196
};

0 commit comments

Comments
 (0)